Expand description
§MAVKit
Async MAVLink SDK for vehicle control, telemetry, missions, and parameters. Available as a Rust crate and a Python package with full async support.
§Install
Python
pip install mavkitRust
[dependencies]
mavkit = "0.3"
tokio = { version = "1", features = ["macros", "rt-multi-thread"] }§Quick Start
§Python
import asyncio
import mavkit
async def main():
vehicle = await mavkit.Vehicle.connect_udp("0.0.0.0:14550")
state = await vehicle.wait_state()
print(f"mode={state.mode_name} armed={state.armed}")
telem = await vehicle.wait_telemetry()
print(f"alt={telem.altitude_m} bat={telem.battery_pct}")
await vehicle.disconnect()
asyncio.run(main())§Rust
use mavkit::Vehicle;
#[tokio::main]
async fn main() -> Result<(), Box<dyn std::error::Error>> {
let vehicle = Vehicle::connect_udp("0.0.0.0:14550").await?;
let mut state_rx = vehicle.state();
state_rx.changed().await?;
let state = state_rx.borrow().clone();
println!("mode={} armed={}", state.mode_name, state.armed);
vehicle.disconnect().await?;
Ok(())
}§Features
- Connections – UDP, TCP, serial, BLE/SPP via byte-stream adapters
- Telemetry – reactive watch channels (Rust) / sync properties + async waiters (Python)
- Commands – arm, disarm, set mode, takeoff, guided goto, arbitrary COMMAND_LONG
- Missions – upload, download, clear, set current, verify roundtrip
- Parameters – download all, write single, batch write,
.paramfile I/O - Validation – plan validation, normalization, tolerance-based comparison
§Feature Flags (Rust)
| Flag | Default | Description |
|---|---|---|
udp | Yes | MAVLink UDP transport |
tcp | No | MAVLink TCP transport |
serial | Yes | MAVLink direct serial transport |
ardupilot | Yes | ArduPilot mode-name mapping |
stream | No | Byte-stream adapters for BLE/SPP/custom links |
tlog | No | TLOG file parser for timestamped MAVLink logs |
§Mission Wire Semantics
For MissionType::Mission, MAVLink wire transfer is normalized:
- Upload: a home item is prepended at
seq=0(or a zero placeholder if missing) - Download: wire
seq=0is extracted as home; remaining items are resequenced from 0
For Fence and Rally types, items pass through unchanged.
§Examples
Rust – see examples/:
cargo run --example connect_udpPython – see mavkit-python/examples/:
cd mavkit-python && uv run python examples/connect_udp.py§Development
§Rust
cargo check
cargo clippy --all-targets --all-features -- -D warnings
cargo test
cargo fmt --all -- --check§Python
cd mavkit-python
uv sync
uv run maturin develop
uv run ruff format --check .
uv run ruff check .§SITL Integration Tests
Requires Docker + ArduPilot SITL:
make bridge-up # start SITL + MAVProxy bridge
make test-sitl # run integration tests
make bridge-down # cleanupEnvironment: MAVKIT_SITL_UDP_BIND (default 0.0.0.0:14550), MAVKIT_SITL_STRICT (set 1 for strict mode).
§License
MIT
Re-exports§
pub use config::VehicleConfig;pub use error::VehicleError;pub use vehicle::Vehicle;pub use state::Attitude;pub use state::AutopilotType;pub use state::Battery;pub use state::FlightMode;pub use state::Gps;pub use state::GpsFixType;pub use state::LinkState;pub use state::MavSeverity;pub use state::MissionState;pub use state::Position;pub use state::RcChannels;pub use state::StatusMessage;pub use state::SystemStatus;pub use state::Telemetry;pub use state::Terrain;pub use state::VehicleIdentity;pub use state::VehicleState;pub use state::VehicleType;pub use mission::CompareTolerance;pub use mission::HomePosition;pub use mission::IssueSeverity;pub use mission::MissionFrame;pub use mission::MissionHandle;pub use mission::MissionIssue;pub use mission::MissionItem;pub use mission::MissionPlan;pub use mission::MissionTransferMachine;pub use mission::MissionType;pub use mission::RetryPolicy;pub use mission::TransferDirection;pub use mission::TransferError;pub use mission::TransferEvent;pub use mission::TransferPhase;pub use mission::TransferProgress;pub use mission::items_for_wire_upload;pub use mission::normalize_for_compare;pub use mission::plan_from_wire_download;pub use mission::plans_equivalent;pub use mission::validate_plan;pub use params::Param;pub use params::ParamProgress;pub use params::ParamStore;pub use params::ParamTransferPhase;pub use params::ParamType;pub use params::ParamWriteResult;pub use params::ParamsHandle;pub use params::format_param_file;pub use params::parse_param_file;