Async PX4 drone controller — sequential autonomous flight via MAVLink
Project description
mavpilot
Асинхронный контроллер PX4-дрона на Python — последовательное автономное управление через MAVLink, встроенная 3D-визуализация в браузере и режим без железа.
Возможности
| Чистый asyncio API | Пишите последовательную логику миссии через await — без колбэков и машин состояний |
| PX4 OFFBOARD режим | Стримит SET_POSITION_TARGET_LOCAL_NED на частоте 50 Гц |
| Точная посадка | Визуально-направляемый спуск через простой callback API |
| Движение в теле дрона | goto_body_relative() без ручного пересчёта NED/курс |
| Ограничение скорости рыскания | Плавные переходы курса (по умолчанию 15 °/с, настраивается) |
| Визуализация в браузере | Живая 3D-траектория + телеметрия через HTTP+SSE — без npm, без CDN |
| Mock-режим | Встроенный физический симулятор — тестируйте миссию без SITL и железа |
| Потокобезопасность | Heartbeat, receiver и streamer крутятся в фоновых потоках |
Установка
pip install mavpilot
Или из исходников:
git clone https://github.com/Onikore/mavpilot
cd mavpilot
pip install -e ".[dev]"
Зависимость времени выполнения: pymavlink (устанавливается автоматически).
Быстрый старт — mock-режим
Дрон и SITL не нужны:
# Квадратная траектория
python -m mavpilot --mock
# Траектория в виде звезды
python -m mavpilot --mock --pattern star
# Демо точной посадки
python -m mavpilot --mock --precision-land
Откройте http://localhost:8765 в браузере — увидите живую 3D-визуализацию.
Использование как библиотека
import asyncio
from mavpilot import DroneController
async def mission():
# `async with` подключается на входе и завершает работу на выходе (aclose());
# если блок выходит из-за исключения и дрон ещё в воздухе — сначала
# вызывается emergency_land().
async with DroneController(
connection_string="udp:127.0.0.1:14540", # SITL по умолчанию
enable_viz=True, # визуализация в браузере на :8765
) as drone:
await drone.apply_safe_params() # рекомендуемые параметры безопасности PX4
await drone.wait_until_ready() # ждём EKF / LOCAL_POSITION_NED
await drone.takeoff(altitude_m=5.0)
# Координаты NED (x=Север, y=Восток, z=Вниз)
await drone.goto(x=10, y=0, z=-5)
await drone.goto(x=10, y=10, z=-5, yaw_deg=90)
await drone.goto_body_relative(forward_m=5, right_m=0, down_m=0)
await drone.hover(duration_s=3.0)
await drone.land()
asyncio.run(mission())
Точная посадка
Передайте callback, возвращающий смещение маркера в системе координат тела дрона (FRD):
from mavpilot import DroneController, MarkerObservation
def get_marker() -> MarkerObservation | None:
# подключите свой визуальный пайплайн
# dx = смещение вперёд (м), dy = смещение вправо (м)
return MarkerObservation(dx=0.3, dy=-0.1)
async def mission():
async with DroneController(mock=True, enable_viz=False) as drone:
await drone.takeoff(altitude_m=10.0)
result = await drone.precision_land(
get_marker_offset=get_marker,
descent_rate_mps=0.3,
final_altitude_m=0.5,
horizontal_tolerance_m=0.15,
min_altitude_floor_m=0.3, # новый параметр в v0.2.0
)
if not result:
# status ∈ {ABORTED_AT_FLOOR, MARKER_LOST, TIMEOUT}
print(f"precision_land не приземлился: {result.status.value}")
print(f"финальная позиция: {result.final_position}")
Перевод пикселей камеры в смещение в теле дрона
from mavpilot.utils import pixel_to_body_offset
dx, dy = pixel_to_body_offset(
px_norm_x=0.1, # нормализованные координаты [-1, 1]
px_norm_y=-0.05,
camera_hfov_deg=90.0,
camera_vfov_deg=60.0,
altitude_above_ground_m=drone.get_local_position().altitude,
camera_mount_yaw_deg=0.0,
)
CLI
python -m mavpilot [ОПЦИИ]
Опции:
--connection STR MAVLink endpoint [по умолчанию: udp:127.0.0.1:14540]
--mock Симуляторный режим без железа
--viz-port INT Порт браузерной визуализации [по умолчанию: 8765]
--viz-host STR Интерфейс визуализатора [по умолчанию: 127.0.0.1]
Используйте 0.0.0.0 для доступа из локальной сети
--no-viz Отключить браузерную визуализацию
--precision-land Точная посадка с симулированным маркером
--pattern {square,star} Паттерн полёта в демо [по умолчанию: square]
Поведение при ошибках и Ctrl-C
- Ctrl-C в любой момент миссии вызывает
emergency_land(). Это включает: смену режима наAUTO_LAND, ожидание касания земли (до 10 с), отправку командыMAV_CMD_NAV_LANDесли режим завис, и в крайнем случаеDO_FLIGHTTERMINATION(мгновенное обесточивание моторов — дрон падает). - RTL не входит в
emergency_land(). Возврат на точку старта — это отдельная штатная операция (drone.return_to_launch()), не аварийная. - Любое необработанное исключение в миссии (включая
KeyboardInterrupt) также вызываетemergency_land().
Watchdog телеметрии и протокольная безопасность (v0.2.0)
- Watchdog телеметрии —
telemetry_watchdog_s(по умолчанию 2 с). Если за это окно не приходит свежийLOCAL_POSITION_NED, стример выставляет флаг watchdog, и следующий вызов миссии (takeoff/goto/set_yaw/land/return_to_launch/precision_land) бросаетDroneError.emergency_land()намеренно игнорирует флаг — это путь восстановления, ради которого watchdog и срабатывает. - Проверка здоровья EKF —
wait_until_ready()теперь проверяет ещё и здоровье EKF AHRS (SYS_STATUS, бит 5), а не только свежесть позиции. send_command_long()— даёт доступ к COMMAND_ACK через Future: ожидает финальный ACK по ключу(cmd_id, target_sys, target_comp).IN_PROGRESSпродлевает дедлайн; дубликат команды в полёте, таймаут или не-ACCEPTEDрезультат бросаютDroneError.get_yaw_deg()нормализован к[-180, 180].
Справочник API
DroneController(…)
DroneController(
connection_string = "udp:127.0.0.1:14540",
source_system = 255,
source_component = MAV_COMP_ID_MISSIONPLANNER,
loop_hz = 50.0, # частота стриминга сетпоинтов
enable_viz = True, # запустить браузерную визуализацию
viz_port = 8765,
mock = False, # симулятор без железа
yaw_slew_rate_deg = 15.0, # макс. скорость рыскания (°/с)
)
Методы управления полётом
| Метод | Описание |
|---|---|
await connect(timeout_s) |
Открыть MAVLink и запустить фоновые потоки |
await apply_safe_params() |
Записать рекомендуемые параметры безопасности PX4 |
await wait_until_ready(timeout_s) |
Ждать пока EKF не выдаст LOCAL_POSITION_NED |
await takeoff(altitude_m, timeout_s) |
Арм, OFFBOARD режим, набор высоты |
await goto(x, y, z, yaw_deg, …) |
Лететь в точку NED |
await goto_relative(dx, dy, dz, …) |
Смещение от текущей позиции NED |
await goto_body_relative(fwd, right, down, …) |
Смещение в системе тела дрона |
await set_yaw(yaw_deg, timeout_s) |
Разворот на месте |
await hover(duration_s) |
Удерживать позицию |
await land(timeout_s) |
AUTO_LAND, ждать приземления |
await precision_land(callback, …) |
Визуально-направляемый спуск; возвращает PrecisionLandResult |
await return_to_launch(timeout_s) |
AUTO_RTL, ждать приземления |
await emergency_land() |
Цепочка: AUTO_LAND → NAV_LAND → DO_FLIGHTTERMINATION |
await aclose() / async with |
Остановить потоки и закрыть соединение (рекомендуется) |
close() |
Синхронное завершение (устарело; используйте aclose()) |
Телеметрия
| Метод | Возвращает |
|---|---|
get_local_position() |
Position(x, y, z) в метрах NED |
get_yaw_rad() / get_yaw_deg() |
Текущий курс |
is_armed() |
bool |
is_offboard() |
bool |
landed_state() |
int (1 = на земле, 2 = в воздухе) |
Датаклассы
from mavpilot import Position, MarkerObservation
# Позиция в NED (x=Север, y=Восток, z=Вниз)
pos: Position # pos.altitude == -pos.z
# Смещение маркера в системе тела дрона FRD
obs: MarkerObservation # dx=вперёд, dy=вправо, dz=вниз (опционально)
Система координат
mavpilot использует NED-конвенцию PX4 из LOCAL_POSITION_NED:
| Ось | Направление | Примечание |
|---|---|---|
| x | Север (+) | |
| y | Восток (+) | |
| z | Вниз (+) | высота = -z |
Утилиты для преобразования координат:
from mavpilot.utils import body_to_ned, ned_to_body, pixel_to_body_offset
Визуализация
Лёгкий встроенный HTTP+SSE сервер раздаёт 3D-вид на Three.js без сборки и пакетного менеджера. Откройте http://localhost:8765 пока дрон работает.
Правая панель отображает:
- Статус арма и режим полёта
- Позицию, скорость, курс, заряд батареи в реальном времени
- Активный сетпоинт
- Лог команд (взлёт, goto, посадка, …)
- Сообщения PX4 STATUSTEXT
UI состоит из нативных ES-модулей, раздаваемых из mavpilot/viz/static/ (index.html + styles.css + main.js/scene.js/sse.js/telemetry.js/log.js) — без сборщика, но нужен современный браузер с поддержкой ES-модулей. Параметр max_clients (по умолчанию 32) ограничивает число одновременных SSE-подключений; лишним клиентам возвращается HTTP 503.
Архитектура
asyncio event loop <-- ваш код миссии
|
v
DroneController
|
+-- heartbeat_thread (1 Гц MAVLink heartbeat)
+-- receiver_thread (разбор входящих MAVLink → self._tel)
+-- streamer_thread (публикация SET_POSITION_TARGET_LOCAL_NED @ 50 Гц)
+-- viz_server (опциональный HTTP+SSE → браузер)
Всё общее состояние защищено _tel_lock и _setpoint_lock. В коде миссии asyncio-примитивы не нужны.
Структура модулей (v0.2.0)
mavpilot/
├── controller.py # Фасад DroneController (корень композиции)
├── _connection.py # MAVLinkConnection — pymavlink + лок I/O + heartbeat/receiver
├── _telemetry.py # Telemetry — разбор входящих сообщений + кэш состояния
├── _commands.py # CommandSender — COMMAND_LONG с маршрутизацией ACK через Future
├── _streamer.py # OffboardStreamer — поток сетпоинтов + watchdog телеметрии
├── _mission.py # MissionOps — takeoff/goto/hover/land/rtl/emergency_land
├── _precision_land.py # PrecisionLand — визуальный спуск с нижним порогом высоты
├── _safety.py # SafetyOps — wait_until_ready
├── _mock.py # MockMavConnection + встроенный симулятор
├── errors.py # DroneError
├── types.py # Position, MarkerObservation, PrecisionLand{Status,Result}
├── utils.py # преобразования координат, pinhole, нормализация курса
├── constants.py # биты режимов PX4, id MAV_CMD, type_mask
├── cli.py # точка входа argparse
└── viz.py # сервер браузерного UI (HTTP + SSE)
Каждый MAVLink send и recv проходит через MAVLinkConnection, владеющий единственным локом. Каждый подкомпонент получает зависимости через конструктор — легко мокать в тестах.
Подключение к реальному железу
# UART (Raspberry Pi <-> Pixhawk)
drone = DroneController(connection_string="/dev/ttyAMA0")
# UDP (SITL или мост компаньон-компьютер → GCS)
drone = DroneController(connection_string="udp:192.168.1.10:14540")
# TCP
drone = DroneController(connection_string="tcp:127.0.0.1:5760")
Рекомендуемые параметры безопасности (устанавливаются через apply_safe_params()):
| Параметр | Значение | Назначение |
|---|---|---|
COM_RCL_EXCEPT |
7 | Нет failsafe в offboard / mission / hold |
COM_OBL_RC_ACT |
4 | Потеря RC → hold, не RTL |
COM_OF_LOSS_T |
2.0 с | Таймаут потери offboard |
COM_RC_IN_MODE |
1 | RC не требуется |
Разработка
# Установка в editable-режиме с dev-зависимостями
pip install -e ".[dev]"
# Тесты
pytest -q
# Линтер
ruff check mavpilot/
# Проверка типов
mypy mavpilot/
Лицензия
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
Built Distribution
Filter files by name, interpreter, ABI, and platform.
If you're not sure about the file name format, learn more about wheel file names.
Copy a direct link to the current filters
File details
Details for the file mavpilot-0.2.0.tar.gz.
File metadata
- Download URL: mavpilot-0.2.0.tar.gz
- Upload date:
- Size: 49.8 kB
- Tags: Source
- Uploaded using Trusted Publishing? Yes
- Uploaded via: twine/6.1.0 CPython/3.13.12
File hashes
| Algorithm | Hash digest | |
|---|---|---|
| SHA256 |
2f97d3f9ee571badf6a49711c4cade075687c1a89217dce0067f10673126e355
|
|
| MD5 |
c5754109cd17698a347d0de203a87623
|
|
| BLAKE2b-256 |
020ead07478f374f20ddb11f63d5cdc624649208b5dd63187b22db61cdbc14d3
|
Provenance
The following attestation bundles were made for mavpilot-0.2.0.tar.gz:
Publisher:
ci.yml on Onikore/mavpilot
-
Statement:
-
Statement type:
https://in-toto.io/Statement/v1 -
Predicate type:
https://docs.pypi.org/attestations/publish/v1 -
Subject name:
mavpilot-0.2.0.tar.gz -
Subject digest:
2f97d3f9ee571badf6a49711c4cade075687c1a89217dce0067f10673126e355 - Sigstore transparency entry: 1667295469
- Sigstore integration time:
-
Permalink:
Onikore/mavpilot@47f90110aada00d3b18da4493dd7a2ec3db43b20 -
Branch / Tag:
refs/tags/v0.2.0 - Owner: https://github.com/Onikore
-
Access:
public
-
Token Issuer:
https://token.actions.githubusercontent.com -
Runner Environment:
github-hosted -
Publication workflow:
ci.yml@47f90110aada00d3b18da4493dd7a2ec3db43b20 -
Trigger Event:
push
-
Statement type:
File details
Details for the file mavpilot-0.2.0-py3-none-any.whl.
File metadata
- Download URL: mavpilot-0.2.0-py3-none-any.whl
- Upload date:
- Size: 52.0 kB
- Tags: Python 3
- Uploaded using Trusted Publishing? Yes
- Uploaded via: twine/6.1.0 CPython/3.13.12
File hashes
| Algorithm | Hash digest | |
|---|---|---|
| SHA256 |
47a2785c53ddec4a75cb05e602cd944f67e64fd115684ed7e531d8293a038860
|
|
| MD5 |
4d2a0d6d8e67fb447c32c36a9d981cda
|
|
| BLAKE2b-256 |
ea2dc6b2872eec80f136c19db733e1f63fb8c96416fa1e43646234d77fcf6151
|
Provenance
The following attestation bundles were made for mavpilot-0.2.0-py3-none-any.whl:
Publisher:
ci.yml on Onikore/mavpilot
-
Statement:
-
Statement type:
https://in-toto.io/Statement/v1 -
Predicate type:
https://docs.pypi.org/attestations/publish/v1 -
Subject name:
mavpilot-0.2.0-py3-none-any.whl -
Subject digest:
47a2785c53ddec4a75cb05e602cd944f67e64fd115684ed7e531d8293a038860 - Sigstore transparency entry: 1667295569
- Sigstore integration time:
-
Permalink:
Onikore/mavpilot@47f90110aada00d3b18da4493dd7a2ec3db43b20 -
Branch / Tag:
refs/tags/v0.2.0 - Owner: https://github.com/Onikore
-
Access:
public
-
Token Issuer:
https://token.actions.githubusercontent.com -
Runner Environment:
github-hosted -
Publication workflow:
ci.yml@47f90110aada00d3b18da4493dd7a2ec3db43b20 -
Trigger Event:
push
-
Statement type: