neelsani/mavlink-zig
MAVLink protocol implementation in Zig
c0bda4f35ea61cfb7845337adfa255c86c67fd13
A lightweight, zero-dependency, zero-allocation MAVLink v2.0 protocol implementation in Zig, designed for embedded systems and high-performance applications.
MAVLink (Micro Air Vehicle Link) is a lightweight messaging protocol for communicating with drones, robotics systems, and other autonomous vehicles. Key features:
This library brings MAVLink to Zig with full type safety and no runtime overhead.
Add to your project using Zig's package manager:
# For stable Zig releases (recommended for production):
zig fetch --save https://github.com/neelsani/mavlink-zig/archive/refs/tags/vX.Y.Z.tar.gz
# For Zig master branch compatibility:
zig fetch --save git+https://github.com/neelsani/mavlink-zig
Then add the following to build.zig
:
const mavlink = b.dependency("mavlink", .{});
exe.root_module.addImport("mavlink", mavlink.module("mavlink"));
examples/
directory.To run an individual example, use Zig's build system. Replace <name of example folder>
with the specific example you want to run. For instance, to run the net
example:
zig build net
Hereβs a minimal example of how to parse a MAVLink heartbeat message using the library:
const std = @import("std"); // Import Zigβs standard library
const net = std.net; // Bring networking APIs into scope
const mavlink = @import("mavlink"); // Import the MAVLink library
const D = mavlink.dialects.common; // Alias the βcommonβ dialect for convenience
pub fn main() !void {
// Establish a TCP connection to the MAVLink endpoint (e.g., SITL at 127.0.0.1:8888)
const conn = try net.tcpConnectToAddress(try net.Address.parseIp4("127.0.0.1", 8888));
defer conn.close(); // Ensure the connection is closed on exit
// -----------------------------------------------------------------------
// Build a HEARTBEAT message, acting as a Ground Control Station (GCS)
// -----------------------------------------------------------------------
const hb = D.messages.HEARTBEAT{
.type = .MAV_TYPE_GCS, // Identify as GCS
.autopilot = .MAV_AUTOPILOT_INVALID, // Not a flight controller
.base_mode = @intFromEnum(D.enums.MAV_MODE.MAV_MODE_AUTO_ARMED),
// Armed in AUTO mode
.custom_mode = 0, // No custom mode flags
.system_status = .MAV_STATE_STANDBY, // Standby state
.mavlink_version = 3, // MAVLink v2.0 identifier
};
// Prepare a buffer large enough for any v2 packet
var buf: [mavlink.v2.MAVLINK_MAX_PACKET_SIZE]u8 = undefined;
// Serialize the HEARTBEAT into the buffer slice, get the byte count
const len = try mavlink.v2.writeMessageToSlice(buf[0..], hb);
// Send the serialized packet over the TCP connection
try conn.writer().writeAll(buf[0..len]);
// -----------------------------------------------------------------------
// Initialize the MAVLink v2 parser for incoming data
// -----------------------------------------------------------------------
var parser = mavlink.v2.init();
// A temporary read buffer for incoming TCP data
var readBuf: [512]u8 = undefined;
// Continuously read incoming bytes and feed them to the parser
while (true) {
const n = try conn.reader().read(&readBuf); // Read up to `readBuf.len` bytes
for (readBuf[0..n]) |b| { // Iterate each received byte
if (parser.parseChar(b)) |msg| { // If a full MAVLink message is parsed
// Check if itβs a HEARTBEAT response
if (msg.msgid == D.messages.HEARTBEAT.MSG_ID) {
// Deserialize the payload into a HEARTBEAT struct
const reply = try mavlink.serde.deserialize(D.messages.HEARTBEAT, msg.payload[0..msg.len]);
// Print the received heartbeat in debug output
std.debug.print("GCS got HEARTBEAT: {any}\n", .{reply});
}
}
}
}
}
Note:
For more complete and advanced examples, check out theexamples/
directory.
For detailed documentation and the full API reference, visit:
http://mavlink-zig.neels.dev/
For support, email [email protected].