Skip to main content

Pymavlink wrappers for easy drone control developped by Zenith Polymtl

Project description

Zenmav – Drone Control Library

License

Zenmav is a lightweight Python wrapper that lets you write five-line flight scripts for ArduPilot-controlled drones in either SITL or real hardware. Developed by Zenith Polytechnique Montréal.

Key Features

  • Simplified Pymavlink Commands with Feedback – one-line TCP/UDP connection with heartbeat check and easy mode change
  • Precise Navigation
    • Global GPS waypoints with user-defined accuracy
    • Local NED waypoints relative to home
    • Real-time body-frame speed control
  • Autonomous Area Scans
    • Spiral pattern
    • Rectilinear/lawn-mower pattern
  • Live Telemetry – local position, global GPS, heading, RC channels
  • CSV Logging Utilities

Safety Disclaimer

Always test new scripts in SITL first.
When flying a real aircraft you are solely responsible for airworthiness, regulatory compliance and safe operation.
Operate in a clear area, keep visual line-of-sight and have a manual RC transmitter ready to take over. It is highly recommended NOT to use the arming command inside a script for a real drone unless thoroughly tested.


Installation

pip install zenmav

SITL users only need MAVProxy running on port 5762 (default shown below).


Quick Start

Below are three concise, copy-paste-ready examples that showcase different parts of Zenmav’s API.
Each script follows the same basic pattern—connect, arm, fly, land—while using a different feature set.


Example 1 — Fly to a local waypoint and come back

# example_local_target.py
# Demonstrates local_target()    (requires zenmav 0.0.5)

import time
from zenmav.core import Zenmav

def main() -> None:
    drone = Zenmav()                 # connect (default SITL TCP link)
    drone.arm()
    drone.set_mode("GUIDED")
    drone.takeoff(altitude=15)       # climb to 15 m AGL

    # Fly 30 m North, 20 m East, keep same altitude (Down = 0)
    print("Navigating to local waypoint …")
    drone.local_target([30, 20, 0])

    # Hold position 5 s
    time.sleep(5)

    # Return-to-Launch (waits for landing & disarm)
    drone.RTL()

if __name__ == "__main__":
    main()

Example 2 — Quick spiral scan of a 50 m radius area

# example_spiral_scan.py
# Demonstrates spiral_scan()     (requires zenmav 0.0.5)

from zenmav.core import Zenmav

def main() -> None:
    drone = Zenmav(gps_thresh=2)     # enables waypoint-reach detection in metres
    drone.arm()
    drone.set_mode("GUIDED")
    drone.takeoff(altitude=25)       # climb to 25 m AGL

    print("Starting spiral scan …")
    drone.spiral_scan(
        largeur_detection=8,         # 8 m sensor footprint
        altitude=25,                 # keep current altitude
        rayon_scan=50,               # cover a 50 m radius
        safety_margin=10             # add 10 m buffer
    )

    drone.RTL()

if __name__ == "__main__":
    main()

Example 3 — Log a GPS point to CSV and adjust cruise speed

# example_csv_and_params.py
# Shows get_global_pos(), insert_coordinates_to_csv(), set_param()   (zenmav 0.0.5)

import csv
from pathlib import Path
from zenmav.core import Zenmav

CSV_FILE = Path("waypoints.csv")

def main() -> None:
    drone = Zenmav(ip="/dev/ttyACM0") # example connection to pixhawk via USB
    drone.arm()
    drone.set_mode("GUIDED")
    drone.takeoff(altitude=10)

    # Grab current location and write it to CSV
    lat, lon, rel_alt = drone.get_global_pos()
    desc = "Take-off point"
    drone.insert_coordinates_to_csv(CSV_FILE, (lat, lon), desc)
    print(f"Saved home waypoint to {CSV_FILE}")

    # Slow the aircraft to 3 m/s (ArduPilot expects cm/s)
    drone.set_param("WPNAV_SPEED", 300)
    print("WPNAV_SPEED set to 3 m/s")

    # Fly forward at 3 m/s for ~3 s using body-frame velocity
    for _ in range(30):
        drone.speed_target([3, 0, 0])     # 3 m/s forward, level flight
    print("Short cruise complete")

    drone.RTL()

    # Optional: show CSV content
    print("\nCSV content:")
    with CSV_FILE.open() as fp:
        print(fp.read())

if __name__ == "__main__":
    main()

Zenmav Docs

Available in docs/zenmav.md


Troubleshooting

Symptom Fix
No heartbeat in 5 seconds Check connection string / firewall
PermissionError: ttyACM0 sudo usermod -aG dialout $USER
Waypoint never “reached” Provide gps_thresh at construction
Takeoff not working Make sure to be in Guided mode

Contributing

Issues and pull requests are welcome!
Please fork the repository, create a feature branch and open an MR when ready.


Project details


Download files

Download the file for your platform. If you're not sure which to choose, learn more about installing packages.

Source Distribution

zenmav-0.0.7.tar.gz (12.8 kB view details)

Uploaded Source

Built Distribution

If you're not sure about the file name format, learn more about wheel file names.

zenmav-0.0.7-py3-none-any.whl (10.6 kB view details)

Uploaded Python 3

File details

Details for the file zenmav-0.0.7.tar.gz.

File metadata

  • Download URL: zenmav-0.0.7.tar.gz
  • Upload date:
  • Size: 12.8 kB
  • Tags: Source
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/6.1.0 CPython/3.10.12

File hashes

Hashes for zenmav-0.0.7.tar.gz
Algorithm Hash digest
SHA256 e6a3cedb8b8b9816fc7d97317141805e78f4c16d0c7f68441a98237a53cf43a2
MD5 ff3af8034a62b05d82454c417b549a1b
BLAKE2b-256 de6b1dc3714fe16dd6ba8068c33c32052cab4d81b02c3d8c533a5b5a3c2c750c

See more details on using hashes here.

File details

Details for the file zenmav-0.0.7-py3-none-any.whl.

File metadata

  • Download URL: zenmav-0.0.7-py3-none-any.whl
  • Upload date:
  • Size: 10.6 kB
  • Tags: Python 3
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/6.1.0 CPython/3.10.12

File hashes

Hashes for zenmav-0.0.7-py3-none-any.whl
Algorithm Hash digest
SHA256 40d9e7aa2c49b99176eb89b82268c2bbc84e5359e87ecf3b4b993b69788667d6
MD5 67d979b35299f5c3e7f4fef549549002
BLAKE2b-256 9e158d2db6dc40008fd0b2cd5cd972270c4491d5e035e56920139161e74c345c

See more details on using hashes here.

Supported by

AWS Cloud computing and Security Sponsor Datadog Monitoring Depot Continuous Integration Fastly CDN Google Download Analytics Pingdom Monitoring Sentry Error logging StatusPage Status page