Compare commits

...

10 Commits

Author SHA1 Message Date
akiroz 263528061d
impl vector_table generation for wch ch32 2 months ago
akiroz b5d657a009
impl bsp for ch32v003xx 2 months ago
Arkadiusz Wójcik 3af91ea8f9
USB CDC ACM support + code refactor (#211)
* part1: code refactor

* part2: config serialization

* usb cdc acm support

---------

Co-authored-by: Arkadiusz Wójcik <wojcik.arkadiusz@outlook.com>

@ikskuh
2 months ago
Vesim 063ade2a3c
fix(rp2040) apply broken codegen workaround to both busy loop (#219) 2 months ago
Vesim fca0bf2bff
fixup! enable atsamd51j19 fpu (#196) (#218) 2 months ago
biom4st3r c30f71f33f
Basic support for ATmega32u4 (#195)
Co-authored-by: Vesim <vesim809+github@protonmail.com>
2 months ago
Stevie Hryciw 56e08d653c
rp2040: remove redendant code in I2C.apply() (#212) 2 months ago
Jacob Young 4d3d5cce0d
enable atsamd51j19 fpu (#196) 2 months ago
biom4st3r fcb68ad0e2
Updated to zig 0.13.0 (#198)
* Updated to latest zig

* feat(flake): update zig to 0.13.0 and add zls

This also disable diffs for flake.lock to not
not polute the git diff output too much

* feat(build): Update dependencies to support 0.13.0

* feat(build): disable broken examples

* feat(ci): Update zig to 0.13.0

* feat(rp2040): Update pio tokenizer tests to 0.13.0

* feat(build): Fix uses of deprecated std.zig.CrossTarget

* feat(rezg): Fix uses of deprecated std.mem.{tokenize,slice}

* feat(rp2040): Fix uses of depreacted std.rand

* feat(readme): Update zig version

---------

Co-authored-by: Maciej 'vesim' Kuliński <vesim809@pm.me>
2 months ago
Matthias bb8888944f
Use app provided panic handler if it exists (#209) 3 months ago

@ -1,2 +1,3 @@
# use_nix
use_flake
if has nix; then
use flake
fi

1
.gitattributes vendored

@ -1 +1,2 @@
*.zig text=auto eol=lf
flake.lock -diff

@ -25,7 +25,7 @@ jobs:
- name: Setup Zig
uses: goto-bus-stop/setup-zig@v2
with:
version: 0.12.0
version: 0.13.0
- name: Build
run: zig build -Doptimize=ReleaseSmall

@ -23,7 +23,7 @@ jobs:
- name: Setup Zig
uses: goto-bus-stop/setup-zig@v2
with:
version: 0.12.0
version: 0.13.0
- name: Extract version
run: echo "MICROZIG_VERSION=$(zig build package -- get-version)" >> $GITHUB_ENV

1
.gitignore vendored

@ -1,5 +1,6 @@
zig-out/
zig-cache/
.zig-cache/
microzig-deploy/
.DS_Store
.gdbinit

@ -8,7 +8,7 @@
## What version of Zig to use
Zig 0.12.0
Zig 0.13.0
## Getting Started With MicroZig

@ -10,7 +10,7 @@ fn path(comptime suffix: []const u8) std.Build.LazyPath {
const esp_riscv = .{
.name = "Espressif RISC-V",
.root_source_file = path("/src/cpus/espressif-riscv.zig"),
.target = std.zig.CrossTarget{
.target = std.Target.Query{
.cpu_arch = .riscv32,
.cpu_model = .{ .explicit = &std.Target.riscv.cpu.generic_rv32 },
.cpu_features_add = std.Target.riscv.featureSet(&.{

@ -17,9 +17,9 @@ pub const chips = struct {
.chip = .{
.name = "ATSAMD51J19A",
.url = "https://www.microchip.com/en-us/product/ATSAMD51J19A",
.cpu = MicroZig.cpus.cortex_m4,
.cpu = MicroZig.cpus.cortex_m4f,
.register_definition = .{
.atdf = .{ .path = build_root ++ "/src/chips/ATSAMD51J19A.atdf" },
.atdf = .{ .cwd_relative = build_root ++ "/src/chips/ATSAMD51J19A.atdf" },
},
.memory_regions = &.{
.{ .kind = .flash, .offset = 0x00000000, .length = 512 * 1024 }, // Embedded Flash

@ -11,6 +11,9 @@ fn path(comptime suffix: []const u8) Build.LazyPath {
const hal = .{
.root_source_file = path("/src/hals/ATmega328P.zig"),
};
const hal32u4 = .{
.root_source_file = path("/src/hals/ATmega32U4.zig"),
};
pub const chips = struct {
pub const atmega328p = MicroZig.Target{
@ -29,6 +32,22 @@ pub const chips = struct {
},
.hal = hal,
};
pub const atmega32u4 = MicroZig.Target{
.preferred_format = .hex,
.chip = .{
.name = "ATmega32U4",
.url = "https://www.microchip.com/en-us/product/ATmega32U4",
.cpu = MicroZig.cpus.avr5,
.register_definition = .{
.json = path("/src/chips/ATmega32U4.json"),
},
.memory_regions = &.{
.{ .offset = 0x000000, .length = 32 * 1024, .kind = .flash },
.{ .offset = 0x800100, .length = 2560, .kind = .ram },
},
},
.hal = hal32u4,
};
};
pub const boards = struct {
@ -55,6 +74,18 @@ pub const boards = struct {
},
};
};
pub const adafruit = struct {
pub const itsybitsy_32u4 = MicroZig.Target{
.preferred_format = .hex,
.chip = chips.atmega32u4.chip,
.hal = hal32u4,
.board = .{
.name = "Adafruit ItsyBitsy 32u4",
.url = "https://cdn-learn.adafruit.com/downloads/pdf/introducting-itsy-bitsy-32u4.pdf",
.root_source_file = path("/src/boards/itsybitsy_32u4.zig"),
},
};
};
};
pub fn build(b: *Build) void {

@ -0,0 +1,35 @@
pub const chip = @import("chip");
pub const clock_frequencies = .{
.cpu = 16_000_000,
};
pub const pin_map = .{
.A0 = "PF7",
.A1 = "PF6",
.A2 = "PF5",
.A3 = "PF4",
.A4 = "PF1",
.A5 = "PF0",
.SCK = "PB1", // PCINT1
.MOSI = "PB2", // PCINT2
.MISO = "PB3", // PCINT3
.D13 = "PC7", // Led
.D12 = "PD6",
.D11 = "PB7",
.D10 = "PB6",
.D9 = "PB5",
.D7 = "PE6",
.D5 = "PC6",
.SCL = "PD0",
.SDA = "PD1",
.D1 = "PD3", // TX
.D0 = "PD2", // RX
.D4 = "PD4",
.D6 = "PD7",
.D8 = "PB4",
};

File diff suppressed because it is too large Load Diff

@ -0,0 +1,200 @@
// Almost an exact clone of ATmega328p
const std = @import("std");
const micro = @import("microzig");
const peripherals = micro.chip.peripherals;
const USART1 = peripherals.USART1;
pub const cpu = micro.cpu;
const Port = enum(u8) {
B = 1,
C = 2,
D = 3,
E = 4,
F = 5,
};
pub const clock = struct {
pub const Domain = enum {
cpu,
};
};
pub fn parsePin(comptime spec: []const u8) type {
const invalid_format_msg = "The given pin '" ++ spec ++ "' has an invalid format. Pins must follow the format \"P{Port}{Pin}\" scheme.";
if (spec.len != 3)
@compileError(invalid_format_msg);
if (spec[0] != 'P')
@compileError(invalid_format_msg);
const pin = struct {
pub const port: Port = std.meta.stringToEnum(Port, spec[1..2]) orelse @compileError(invalid_format_msg);
pub const pin: u3 = std.fmt.parseInt(u3, spec[2..3], 10) catch @compileError(invalid_format_msg);
};
switch (pin.port) {
.B => {},
.C => if (pin.pin < 6) @compileError("Invalid pin: " ++ spec),
.D => {},
.E => if (pin.pin != 2 and pin.pin != 6) @compileError("Invalid pin: " ++ spec),
.F => if (pin.pin == 2 or pin.pin == 3) @compileError("Invalid pin: " ++ spec),
}
return pin;
}
pub const gpio = struct {
fn regs(comptime desc: type) type {
return struct {
// io address
const pin_addr: u5 = 3 * @intFromEnum(desc.port) + 0x00;
const dir_addr: u5 = 3 * @intFromEnum(desc.port) + 0x01;
const port_addr: u5 = 3 * @intFromEnum(desc.port) + 0x02;
// ram mapping
const pin = @as(*volatile u8, @ptrFromInt(0x20 + @as(usize, pin_addr)));
const dir = @as(*volatile u8, @ptrFromInt(0x20 + @as(usize, dir_addr)));
const port = @as(*volatile u8, @ptrFromInt(0x20 + @as(usize, port_addr)));
};
}
pub fn setOutput(comptime pin: type) void {
cpu.sbi(regs(pin).dir_addr, pin.pin);
}
pub fn setInput(comptime pin: type) void {
cpu.cbi(regs(pin).dir_addr, pin.pin);
}
pub fn read(comptime pin: type) micro.gpio.State {
return if ((regs(pin).pin.* & (1 << pin.pin)) != 0)
.high
else
.low;
}
pub fn write(comptime pin: type, state: micro.gpio.State) void {
if (state == .high) {
cpu.sbi(regs(pin).port_addr, pin.pin);
} else {
cpu.cbi(regs(pin).port_addr, pin.pin);
}
}
pub fn toggle(comptime pin: type) void {
cpu.sbi(regs(pin).pin_addr, pin.pin);
}
};
pub const uart = struct {
pub const DataBits = enum {
five,
six,
seven,
eight,
nine,
};
pub const StopBits = enum {
one,
two,
};
pub const Parity = enum {
odd,
even,
};
};
pub fn Uart(comptime index: usize, comptime pins: micro.uart.Pins) type {
if (index != 0) @compileError("Atmega32U4 only has a single uart!");
if (pins.tx != null or pins.rx != null)
@compileError("Atmega32U4 has fixed pins for uart!");
return struct {
const Self = @This();
fn computeDivider(baud_rate: u32) !u12 {
const pclk = micro.clock.get().cpu;
const divider = ((pclk + (8 * baud_rate)) / (16 * baud_rate)) - 1;
return std.math.cast(u12, divider) orelse return error.UnsupportedBaudRate;
}
fn computeBaudRate(divider: u12) u32 {
return micro.clock.get().cpu / (16 * @as(u32, divider) + 1);
}
pub fn init(config: micro.uart.Config) !Self {
const ucsz: u3 = switch (config.data_bits) {
.five => 0b000,
.six => 0b001,
.seven => 0b010,
.eight => 0b011,
.nine => return error.UnsupportedWordSize, // 0b111
};
const upm: u2 = if (config.parity) |parity| switch (parity) {
.even => @as(u2, 0b10), // even
.odd => @as(u2, 0b11), // odd
} else 0b00; // parity disabled
const usbs: u1 = switch (config.stop_bits) {
.one => 0b0,
.two => 0b1,
};
const umsel: u2 = 0b00; // Asynchronous USART
// baud is computed like this:
// f(osc)
// BAUD = ----------------
// 16 * (UBRRn + 1)
const ubrr_val = try computeDivider(config.baud_rate);
USART1.UCSR1A.modify(.{
.MPCM1 = 0,
.U2X1 = 0,
});
USART1.UCSR1B.write(.{
.TXB81 = 0, // we don't care about these btw
.RXB81 = 0, // we don't care about these btw
.UCSZ12 = @as(u1, @truncate((ucsz & 0x04) >> 2)),
.TXEN1 = 1,
.RXEN1 = 1,
.UDRIE1 = 0, // no interrupts
.TXCIE1 = 0, // no interrupts
.RXCIE1 = 0, // no interrupts
});
USART1.UCSR1C.write(.{
.UCPOL1 = 0, // async mode
.UCSZ1 = @as(u2, @truncate((ucsz & 0x03) >> 0)),
.USBS1 = usbs,
.UPM1 = upm,
.UMSEL1 = umsel,
});
USART1.UBRR1.modify(ubrr_val);
return Self{};
}
pub fn canWrite(self: Self) bool {
_ = self;
return (USART1.UCSR1A.read().UDRE1 == 1);
}
pub fn tx(self: Self, ch: u8) void {
while (!self.canWrite()) {} // Wait for Previous transmission
USART1.UDR1.* = ch; // Load the data to be transmitted
}
pub fn canRead(self: Self) bool {
_ = self;
return (USART1.UCSR1A.read().RXC1 == 1);
}
pub fn rx(self: Self) u8 {
while (!self.canRead()) {} // Wait till the data is received
return USART1.UDR1.*; // Read received data
}
};
}

@ -12,9 +12,9 @@ const build_root = root();
pub fn build(b: *Build) !void {
const unit_tests = b.addTest(.{
.root_source_file = .{ .path = "src/hal.zig" },
.root_source_file = b.path("src/hal.zig"),
});
unit_tests.addIncludePath(.{ .path = "src/hal/pio/assembler" });
unit_tests.addIncludePath(b.path("src/hal/pio/assembler"));
const unit_tests_run = b.addRunArtifact(unit_tests);
const test_step = b.step("test", "Run platform agnostic unit tests");
@ -119,7 +119,7 @@ pub const BootROM = union(enum) {
};
const linker_script = .{
.path = build_root ++ "/rp2040.ld",
.cwd_relative = build_root ++ "/rp2040.ld",
};
const hal = .{
@ -188,8 +188,8 @@ pub fn get_bootrom(mz: *MicroZig, rom: BootROM) Stage2Bootloader {
.root_source_file = null,
});
//rom_exe.linkage = .static;
rom_exe.setLinkerScript(.{ .path = build_root ++ "/src/bootroms/shared/stage2.ld" });
rom_exe.addAssemblyFile(.{ .path = rom_path });
rom_exe.setLinkerScript(.{ .cwd_relative = build_root ++ "/src/bootroms/shared/stage2.ld" });
rom_exe.addAssemblyFile(.{ .cwd_relative = rom_path });
rom_exe.entry = .{ .symbol_name = "_stage2_boot" };
break :blk rom_exe;

@ -20,27 +20,27 @@ const set_bits = @as(u32, 0x2) << 12;
const clear_bits = @as(u32, 0x3) << 12;
pub fn clear_alias_raw(ptr: anytype) *volatile u32 {
return @as(*volatile u32, @ptrFromInt(@intFromPtr(ptr) | clear_bits));
return @ptrFromInt(@intFromPtr(ptr) | clear_bits);
}
pub fn set_alias_raw(ptr: anytype) *volatile u32 {
return @as(*volatile u32, @ptrFromInt(@intFromPtr(ptr) | set_bits));
return @ptrFromInt(@intFromPtr(ptr) | set_bits);
}
pub fn xor_alias_raw(ptr: anytype) *volatile u32 {
return @as(*volatile u32, @ptrFromInt(@intFromPtr(ptr) | xor_bits));
return @ptrFromInt(@intFromPtr(ptr) | xor_bits);
}
pub fn clear_alias(ptr: anytype) @TypeOf(ptr) {
return @as(@TypeOf(ptr), @ptrFromInt(@intFromPtr(ptr) | clear_bits));
return @ptrFromInt(@intFromPtr(ptr) | clear_bits);
}
pub fn set_alias(ptr: anytype) @TypeOf(ptr) {
return @as(@TypeOf(ptr), @ptrFromInt(@intFromPtr(ptr) | set_bits));
return @ptrFromInt(@intFromPtr(ptr) | set_bits);
}
pub fn xor_alias(ptr: anytype) @TypeOf(ptr) {
return @as(@TypeOf(ptr), @ptrFromInt(@intFromPtr(ptr) | xor_bits));
return @ptrFromInt(@intFromPtr(ptr) | xor_bits);
}
pub inline fn tight_loop_contents() void {

@ -79,13 +79,6 @@ pub const I2C = enum(u1) {
i2c.disable();
regs.IC_ENABLE.write(.{
.ENABLE = .{ .value = .DISABLED },
.ABORT = .{ .value = .DISABLE },
.TX_CMD_BLOCK = .{ .value = .NOT_BLOCKED },
.padding = 0,
});
// Configure as a fast-mode master with RepStart support, 7-bit addresses
regs.IC_CON.write(.{
.MASTER_MODE = .{ .value = .ENABLED },

@ -481,7 +481,7 @@ pub const Tokenizer = struct {
};
}
const directives = std.ComptimeStringMap(*const fn (*Tokenizer, u32, *?Diagnostics) TokenizeError!Token, .{
const directives = std.StaticStringMap(*const fn (*Tokenizer, u32, *?Diagnostics) TokenizeError!Token).initComptime(.{
.{ "program", get_program },
.{ "define", get_define },
.{ "origin", get_origin },
@ -527,7 +527,7 @@ pub const Tokenizer = struct {
fn get_jmp(self: *Tokenizer, diags: *?Diagnostics) TokenizeError!Token.Instruction.Payload {
const Condition = Token.Instruction.Jmp.Condition;
const conditions = std.ComptimeStringMap(Condition, .{
const conditions = std.StaticStringMap(Condition).initComptime(.{
.{ "!x", .x_is_zero },
.{ "x--", .x_dec },
.{ "!y", .y_is_zero },
@ -828,7 +828,7 @@ pub const Tokenizer = struct {
};
}
const instructions = std.ComptimeStringMap(*const fn (*Tokenizer, *?Diagnostics) TokenizeError!Token.Instruction.Payload, .{
const instructions = std.StaticStringMap(*const fn (*Tokenizer, *?Diagnostics) TokenizeError!Token.Instruction.Payload).initComptime(.{
.{ "nop", get_nop },
.{ "jmp", get_jmp },
.{ "wait", get_wait },
@ -1588,7 +1588,7 @@ test "tokenize.instr.jmp.value" {
test "tokenize.instr.jmp.conditions" {
const Condition = Token.Instruction.Jmp.Condition;
const cases = std.ComptimeStringMap(Condition, .{
const cases = std.StaticStringMap(Condition).initComptime(.{
.{ "!x", .x_is_zero },
.{ "x--", .x_dec },
.{ "!y", .y_is_zero },
@ -1598,9 +1598,7 @@ test "tokenize.instr.jmp.conditions" {
.{ "!osre", .osre_not_empty },
});
inline for (cases.kvs) |case| {
const op = case.key;
const cond = case.value;
inline for (comptime cases.keys(), comptime cases.values()) |op, cond| {
const tokens = try bounded_tokenize(comptime std.fmt.comptimePrint("jmp {s} my_label", .{op}));
try expect_instr_jmp(.{ .cond = cond, .target = "my_label" }, tokens.get(0));
@ -1762,16 +1760,14 @@ test "tokenize.instr.mov" {
}
const Operation = Token.Instruction.Mov.Operation;
const operations = std.ComptimeStringMap(Operation, .{
const operations = std.StaticStringMap(Operation).initComptime(.{
.{ "!", .invert },
.{ "~", .invert },
.{ "::", .bit_reverse },
});
inline for (.{ "", " " }) |space| {
inline for (operations.kvs) |kv| {
const str = kv.key;
const operation = kv.value;
inline for (comptime operations.keys(), comptime operations.values()) |str, operation| {
const tokens = try bounded_tokenize(comptime std.fmt.comptimePrint("mov x {s}{s}y", .{
str,
space,
@ -1792,7 +1788,7 @@ test "tokenize.instr.irq" {
wait: bool,
};
const modes = std.ComptimeStringMap(ClearWait, .{
const modes = std.StaticStringMap(ClearWait).initComptime(.{
.{ "", .{ .clear = false, .wait = false } },
.{ "set", .{ .clear = false, .wait = false } },
.{ "nowait", .{ .clear = false, .wait = false } },
@ -1800,15 +1796,15 @@ test "tokenize.instr.irq" {
.{ "clear", .{ .clear = true, .wait = false } },
});
inline for (modes.kvs, 0..) |kv, num| {
inline for (comptime modes.keys(), comptime modes.values(), 0..) |key, value, num| {
const tokens = try bounded_tokenize(comptime std.fmt.comptimePrint("irq {s} {}", .{
kv.key,
key,
num,
}));
try expect_instr_irq(.{
.clear = kv.value.clear,
.wait = kv.value.wait,
.clear = value.clear,
.wait = value.wait,
.num = num,
}, tokens.get(0));
}

@ -2,7 +2,7 @@
const std = @import("std");
const assert = std.debug.assert;
const Random = std.rand.Random;
const Random = std.Random;
const microzig = @import("microzig");
const peripherals = microzig.chip.peripherals;
@ -20,11 +20,11 @@ const peripherals = microzig.chip.peripherals;
/// for security systems because the ROSC as entropy source can be
/// compromised. However, it promises at least equal distribution.
pub const Ascon = struct {
state: std.rand.Ascon,
state: Random.Ascon,
counter: usize = 0,
const reseed_threshold = 4096;
const secret_seed_length = std.rand.Ascon.secret_seed_length;
const secret_seed_length = Random.Ascon.secret_seed_length;
pub fn init() @This() {
// Ensure that the system clocks run from the XOSC and/or PLLs
@ -38,10 +38,10 @@ pub const Ascon = struct {
var b: [secret_seed_length]u8 = undefined;
rosc(&b);
return @This(){ .state = std.rand.Ascon.init(b) };
return @This(){ .state = Random.Ascon.init(b) };
}
/// Returns a `std.rand.Random` structure backed by the current RNG
/// Returns a `std.Random` structure backed by the current RNG
pub fn random(self: *@This()) Random {
return Random.init(self, fill);
}

@ -36,25 +36,32 @@ pub const Mask = packed struct(u32) {
};
pub fn reset(mask: Mask) void {
const raw_mask = @as(u32, @bitCast(mask));
const raw_mask: u32 = @bitCast(mask);
RESETS.RESET.raw = raw_mask;
RESETS.RESET.raw = 0;
RESETS.RESET.write_raw(raw_mask);
RESETS.RESET.write_raw(0);
while ((RESETS.RESET_DONE.raw & raw_mask) != raw_mask) {}
wait_for_reset_done(mask);
}
pub inline fn reset_block(mask: Mask) void {
hw.set_alias_raw(&RESETS.RESET).* = @as(u32, @bitCast(mask));
hw.set_alias(RESETS).RESET.write_raw(@bitCast(mask));
}
pub inline fn unreset_block(mask: Mask) void {
hw.clear_alias_raw(&RESETS.RESET).* = @as(u32, @bitCast(mask));
hw.clear_alias(RESETS).RESET.write_raw(@bitCast(mask));
}
pub fn unreset_block_wait(mask: Mask) void {
const raw_mask = @as(u32, @bitCast(mask));
hw.clear_alias_raw(&RESETS.RESET).* = raw_mask;
const raw_mask: u32 = @bitCast(mask);
hw.clear_alias(RESETS).RESET.write_raw(raw_mask);
wait_for_reset_done(mask);
}
inline fn wait_for_reset_done(mask: Mask) void {
const raw_mask: u32 = @bitCast(mask);
// have to bitcast after a read() instead of `RESETS.RESET_DONE.raw` due to
// some optimization bug. While loops will not be optimzed away if the

@ -9,7 +9,12 @@ const peripherals = microzig.chip.peripherals;
/// Human Interface Device (HID)
pub const usb = microzig.core.usb;
pub const types = usb.types;
pub const hid = usb.hid;
pub const cdc = usb.cdc;
pub const vendor = usb.vendor;
pub const templates = usb.templates.DescriptorsConfigTemplates;
pub const utils = usb.UsbUtils;
const rom = @import("rom.zig");
const resets = @import("resets.zig");
@ -30,42 +35,26 @@ pub const Usb = usb.Usb(F);
pub const DeviceConfiguration = usb.DeviceConfiguration;
pub const DeviceDescriptor = usb.DeviceDescriptor;
pub const DescType = usb.DescType;
pub const InterfaceDescriptor = usb.InterfaceDescriptor;
pub const ConfigurationDescriptor = usb.ConfigurationDescriptor;
pub const EndpointDescriptor = usb.EndpointDescriptor;
pub const DescType = usb.types.DescType;
pub const InterfaceDescriptor = usb.types.InterfaceDescriptor;
pub const ConfigurationDescriptor = usb.types.ConfigurationDescriptor;
pub const EndpointDescriptor = usb.types.EndpointDescriptor;
pub const EndpointConfiguration = usb.EndpointConfiguration;
pub const Dir = usb.Dir;
pub const TransferType = usb.TransferType;
pub const Dir = usb.types.Dir;
pub const TransferType = usb.types.TransferType;
pub const Endpoint = usb.types.Endpoint;
pub const utf8ToUtf16Le = usb.utf8Toutf16Le;
pub var EP0_OUT_CFG: usb.EndpointConfiguration = .{
.descriptor = &usb.EndpointDescriptor{
.descriptor_type = usb.DescType.Endpoint,
.endpoint_address = usb.EP0_OUT_ADDR,
.attributes = @intFromEnum(usb.TransferType.Control),
.max_packet_size = 64,
.interval = 0,
},
.endpoint_control_index = null,
.buffer_control_index = 1,
.data_buffer_index = 0,
.next_pid_1 = false,
};
pub var EP0_IN_CFG: usb.EndpointConfiguration = .{
.descriptor = &usb.EndpointDescriptor{
.descriptor_type = usb.DescType.Endpoint,
.endpoint_address = usb.EP0_IN_ADDR,
.attributes = @intFromEnum(usb.TransferType.Control),
.max_packet_size = 64,
.interval = 0,
},
.endpoint_control_index = null,
.buffer_control_index = 0,
.data_buffer_index = 0,
.next_pid_1 = false,
const HardwareEndpoint = struct {
configured: bool,
ep_addr: u8,
next_pid_1: bool,
max_packet_size: u16,
transfer_type: types.TransferType,
endpoint_control_index: usize,
buffer_control_index: usize,
data_buffer_index: usize,
};
// +++++++++++++++++++++++++++++++++++++++++++++++++
@ -118,6 +107,9 @@ pub const buffers = struct {
/// A set of functions required by the abstract USB impl to
/// create a concrete one.
pub const F = struct {
// Fixed number 4, probably should be comptime number up to 16
var endpoints: [4][2]HardwareEndpoint = undefined;
/// Initialize the USB clock to 48 MHz
///
/// This requres that the system clock has been set up before hand
@ -150,7 +142,7 @@ pub const F = struct {
// We now have the stable 48MHz reference clock required for USB:
}
pub fn usb_init_device(device_config: *usb.DeviceConfiguration) void {
pub fn usb_init_device(_: *usb.DeviceConfiguration) void {
// Bring USB out of reset
resets.reset(.{ .usbctrl = true });
@ -264,33 +256,9 @@ pub const F = struct {
.SETUP_REQ = 1,
});
// setup endpoints
for (device_config.endpoints) |ep| {
// EP0 doesn't have an endpoint control index; only process the other
// endpoints here.
if (ep.endpoint_control_index) |epci| {
// We need to compute the offset from the base of USB SRAM to the
// buffer we're choosing, because that's how the peripheral do.
const buf_base = @intFromPtr(buffers.B.get(ep.data_buffer_index));
const dpram_base = @intFromPtr(peripherals.USBCTRL_DPRAM);
// The offset _should_ fit in a u16, but if we've gotten something
// wrong in the past few lines, a common symptom will be integer
// overflow producing a Very Large Number,
const dpram_offset = @as(u16, @intCast(buf_base - dpram_base));
// Configure the endpoint!
modify_endpoint_control(epci, .{
.ENABLE = 1,
// Please set the corresponding bit in buff_status when a
// buffer is done, thx.
.INTERRUPT_PER_BUFF = 1,
// Select bulk vs control (or interrupt as soon as implemented).
.ENDPOINT_TYPE = .{ .raw = @as(u2, @intCast(ep.descriptor.attributes)) },
// And, designate our buffer by its offset.
.BUFFER_ADDRESS = dpram_offset,
});
}
}
@memset(std.mem.asBytes(&endpoints), 0);
endpoint_init(Endpoint.EP0_IN_ADDR, 64, types.TransferType.Control);
endpoint_init(Endpoint.EP0_OUT_ADDR, 64, types.TransferType.Control);
// Present full-speed device by enabling pullup on DP. This is the point
// where the host will notice our presence.
@ -304,7 +272,7 @@ pub const F = struct {
/// reuse `buffer` immediately after this returns. No need to wait for the
/// packet to be sent.
pub fn usb_start_tx(
ep: *usb.EndpointConfiguration,
ep_addr: u8,
buffer: []const u8,
) void {
// It is technically possible to support longer buffers but this demo
@ -313,6 +281,8 @@ pub const F = struct {
// You should only be calling this on IN endpoints.
// TODO: assert!(UsbDir::of_endpoint_addr(ep.descriptor.endpoint_address) == UsbDir::In);
const ep = hardware_endpoint_get_by_address(ep_addr);
// Copy the given data into the corresponding ep buffer
const epbuffer = buffers.B.get(ep.data_buffer_index);
_ = rom.memcpy(epbuffer[0..buffer.len], buffer);
@ -349,7 +319,7 @@ pub const F = struct {
}
pub fn usb_start_rx(
ep: *usb.EndpointConfiguration,
ep_addr: u8,
len: usize,
) void {
// It is technically possible to support longer buffers but this demo
@ -358,6 +328,8 @@ pub const F = struct {
// You should only be calling this on OUT endpoints.
// TODO: assert!(UsbDir::of_endpoint_addr(ep.descriptor.endpoint_address) == UsbDir::Out);
const ep = hardware_endpoint_get_by_address(ep_addr);
// Check which DATA0/1 PID this endpoint is expecting next.
const np: u1 = if (ep.next_pid_1) 1 else 0;
// Configure the OUT:
@ -392,7 +364,7 @@ pub const F = struct {
///
/// One can assume that this function is only called if the
/// setup request falg is set.
pub fn get_setup_packet() usb.SetupPacket {
pub fn get_setup_packet() usb.types.SetupPacket {
// Clear the status flag (write-one-to-clear)
peripherals.USBCTRL_REGS.SIE_STATUS.modify(.{ .SETUP_REC = 1 });
@ -411,7 +383,7 @@ pub const F = struct {
_ = rom.memcpy(setup_packet[0..4], std.mem.asBytes(&spl));
_ = rom.memcpy(setup_packet[4..8], std.mem.asBytes(&sph));
// Reinterpret as setup packet
return std.mem.bytesToValue(usb.SetupPacket, &setup_packet);
return std.mem.bytesToValue(usb.types.SetupPacket, &setup_packet);
}
/// Called on a bus reset interrupt
@ -425,6 +397,11 @@ pub const F = struct {
peripherals.USBCTRL_REGS.ADDR_ENDP.modify(.{ .ADDRESS = addr });
}
pub fn reset_ep0() void {
var ep = hardware_endpoint_get_by_address(Endpoint.EP0_IN_IDX);
ep.next_pid_1 = true;
}
pub fn get_EPBIter(dc: *const usb.DeviceConfiguration) usb.EPBIter {
return .{
.bufbits = peripherals.USBCTRL_REGS.BUFF_STATUS.raw,
@ -432,21 +409,61 @@ pub const F = struct {
.next = next,
};
}
fn hardware_endpoint_get_by_address(ep_addr: u8) *HardwareEndpoint {
const num = Endpoint.num_from_address(ep_addr);
const dir = Endpoint.dir_from_address(ep_addr);
return &endpoints[num][dir.as_number()];
}
pub fn endpoint_init(ep_addr: u8, max_packet_size: u16, transfer_type: types.TransferType) void {
const ep_num = Endpoint.num_from_address(ep_addr);
const ep_dir = Endpoint.dir_from_address(ep_addr);
var ep = hardware_endpoint_get_by_address(ep_addr);
ep.ep_addr = ep_addr;
ep.max_packet_size = max_packet_size;
ep.transfer_type = transfer_type;
ep.next_pid_1 = false;
ep.buffer_control_index = 2 * ep_num + ep_dir.as_number_reversed();
// TODO - some other way to deal with it
ep.data_buffer_index = 2 * ep_num + ep_dir.as_number();
if (ep_num == 0) {
ep.endpoint_control_index = 0;
} else {
ep.endpoint_control_index = 2*ep_num - ep_dir.as_number();
endpoint_alloc(ep, transfer_type);
}
}
fn endpoint_alloc(ep: *HardwareEndpoint, transfer_type: TransferType) void {
const buf_base = @intFromPtr(buffers.B.get(ep.data_buffer_index));
const dpram_base = @intFromPtr(peripherals.USBCTRL_DPRAM);
// The offset _should_ fit in a u16, but if we've gotten something
// wrong in the past few lines, a common symptom will be integer
// overflow producing a Very Large Number,
const dpram_offset = @as(u16, @intCast(buf_base - dpram_base));
// Configure the endpoint!
modify_endpoint_control(ep.endpoint_control_index, .{
.ENABLE = 1,
// Please set the corresponding bit in buff_status when a
// buffer is done, thx.
.INTERRUPT_PER_BUFF = 1,
// Select bulk vs control (or interrupt as soon as implemented).
.ENDPOINT_TYPE = .{ .raw = transfer_type.as_number() },
// And, designate our buffer by its offset.
.BUFFER_ADDRESS = dpram_offset,
});
}
};
// +++++++++++++++++++++++++++++++++++++++++++++++++
// Utility functions
// +++++++++++++++++++++++++++++++++++++++++++++++++
/// Check if the corresponding buffer is available
pub fn buffer_available(
ep: *usb.EndpointConfiguration,
) bool {
const rbc = read_raw_buffer_control(ep.buffer_control_index);
// Bit 11 of the EPn_X_BUFFER_CONTROL register represents the AVAILABLE_0 flag
return ((rbc & 0x400) == 0);
}
pub fn modify_buffer_control(
i: usize,
fields: anytype,
@ -596,9 +613,9 @@ pub fn next(self: *usb.EPBIter) ?usb.EPB {
const epnum = @as(u8, @intCast(lowbit_index >> 1));
// Of the pair, the IN endpoint comes first, followed by OUT, so
// we can get the direction by:
const dir = if (lowbit_index & 1 == 0) usb.Dir.In else usb.Dir.Out;
const dir = if (lowbit_index & 1 == 0) usb.types.Dir.In else usb.types.Dir.Out;
const ep_addr = dir.endpoint(epnum);
const ep_addr = Endpoint.to_address(epnum, dir);
// Process the buffer-done event.
// Process the buffer-done event.
@ -607,17 +624,13 @@ pub fn next(self: *usb.EPBIter) ?usb.EPB {
// corresponds to this address. We could use a smarter
// method here, but in practice, the number of endpoints is
// small so a linear scan doesn't kill us.
var endpoint: ?*usb.EndpointConfiguration = null;
for (self.device_config.endpoints) |ep| {
if (ep.descriptor.endpoint_address == ep_addr) {
endpoint = ep;
break;
}
}
const endpoint = F.hardware_endpoint_get_by_address(ep_addr);
// Buffer event for unknown EP?!
// TODO: if (endpoint == null) return EPBError.UnknownEndpoint;
// Read the buffer control register to check status.
const bc = read_raw_buffer_control(endpoint.?.buffer_control_index);
const bc = read_raw_buffer_control(endpoint.buffer_control_index);
// We should only get here if we've been notified that
// the buffer is ours again. This is indicated by the hw
@ -631,7 +644,7 @@ pub fn next(self: *usb.EPBIter) ?usb.EPB {
// Get a pointer to the buffer in USB SRAM. This is the
// buffer _contents_. See the safety comments below.
const epbuffer = buffers.B.get(endpoint.?.data_buffer_index);
const epbuffer = buffers.B.get(endpoint.data_buffer_index);
// Get the actual length of the data, which may be less
// than the buffer size.
@ -639,7 +652,7 @@ pub fn next(self: *usb.EPBIter) ?usb.EPB {
// Copy the data from SRAM
return usb.EPB{
.endpoint = endpoint.?,
.endpoint_address = ep_addr,
.buffer = epbuffer[0..len],
};
}

@ -190,7 +190,7 @@ pub const boards = struct {
.chip = chips.stm32f303vc.chip,
.board = .{
.name = "STM32F3DISCOVERY",
.root_source_file = .{ .path = build_root ++ "/src/boards/STM32F3DISCOVERY.zig" },
.root_source_file = .{ .cwd_relative = build_root ++ "/src/boards/STM32F3DISCOVERY.zig" },
},
};
@ -199,7 +199,7 @@ pub const boards = struct {
.chip = chips.stm32f407vg.chip,
.board = .{
.name = "STM32F4DISCOVERY",
.root_source_file = .{ .path = build_root ++ "/src/boards/STM32F4DISCOVERY.zig" },
.root_source_file = .{ .cwd_relative = build_root ++ "/src/boards/STM32F4DISCOVERY.zig" },
},
};
@ -208,7 +208,7 @@ pub const boards = struct {
.chip = chips.stm32f407vg.chip,
.board = .{
.name = "STM3240G_EVAL",
.root_source_file = .{ .path = build_root ++ "/src/boards/STM3240G_EVAL.zig" },
.root_source_file = .{ .cwd_relative = build_root ++ "/src/boards/STM3240G_EVAL.zig" },
},
};
@ -217,7 +217,7 @@ pub const boards = struct {
.chip = chips.stm32f429zit6u.chip,
.board = .{
.name = "STM32F429IDISCOVERY",
.root_source_file = .{ .path = build_root ++ "/src/boards/STM32F429IDISCOVERY.zig" },
.root_source_file = .{ .cwd_relative = build_root ++ "/src/boards/STM32F429IDISCOVERY.zig" },
},
};
};

@ -0,0 +1,19 @@
Copyright (c) Zig Embedded Group contributors
This software is provided 'as-is', without any express or implied warranty. In
no event will the authors be held liable for any damages arising from the use
of this software.
Permission is granted to anyone to use this software for any purpose, including
commercial applications, and to alter it and redistribute it freely, subject to
the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim
that you wrote the original software. If you use this software in a product,
an acknowledgment in the product documentation would be appreciated but is
not required.
2. Altered source versions must be plainly marked as such, and must not be
misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.

@ -0,0 +1,3 @@
# ch32
HALs and register definitions for CH32 (WCH) devices

@ -0,0 +1,51 @@
const std = @import("std");
const MicroZig = @import("microzig/build");
const KiB = 1024;
fn path(comptime suffix: []const u8) std.Build.LazyPath {
return .{
.cwd_relative = comptime ((std.fs.path.dirname(@src().file) orelse ".") ++ suffix),
};
}
const wch_qingke_v2 = .{
.name = "WCH QingKe V2",
.root_source_file = path("/src/cpus/wch_qingke_v2.zig"),
.target = std.Target.Query{
.cpu_arch = .riscv32,
.cpu_model = .{ .explicit = &std.Target.riscv.cpu.generic_rv32 },
.cpu_features_add = std.Target.riscv.featureSet(&.{
std.Target.riscv.Feature.e,
std.Target.riscv.Feature.c,
}),
.os_tag = .freestanding,
.abi = .eabi,
},
};
pub const chips = struct {
pub const ch32v003xx = MicroZig.Target{
.preferred_format = .elf,
.chip = .{
.name = "CH32V00xxx",
.cpu = wch_qingke_v2,
.memory_regions = &.{
.{ .offset = 0x0800_0000, .length = 16 * KiB, .kind = .flash },
.{ .offset = 0x2000_0000, .length = 2 * KiB, .kind = .ram },
},
.register_definition = .{
.svd = path("/src/chips/CH32V00xxx.svd"),
},
},
.hal = .{
.root_source_file = path("/src/hals/CH32V003xx.zig"),
},
};
};
pub const boards = struct {};
pub fn build(b: *std.Build) !void {
_ = b.step("test", "Run platform agnostic unit tests");
}

@ -0,0 +1,14 @@
.{
.name = "bsp/wch/ch32",
.version = "0.0.0",
.dependencies = .{
.@"microzig/build" = .{ .path = "../../../build" },
},
.paths = .{
"LICENSE",
"README.md",
"build.zig",
"build.zig.zon",
"src",
},
}

File diff suppressed because it is too large Load Diff

@ -0,0 +1,62 @@
const std = @import("std");
const root = @import("root");
const microzig = @import("microzig");
const assert = std.debug.assert;
pub fn enable_interrupts() void {
asm volatile ("csrsi mstatus, 0b1000");
}
pub fn disable_interrupts() void {
asm volatile ("csrci mstatus, 0b1000");
}
pub fn wfi() void {
asm volatile ("wfi");
}
pub fn wfe() void {
const PFIC = microzig.chip.peripherals.PFIC;
// Treats the subsequent wfi instruction as wfe
PFIC.SCTLR.modify(.{ .WFITOWFE = 1 });
asm volatile ("wfi");
}
pub const startup_logic = struct {
extern fn microzig_main() noreturn;
pub fn _start() callconv(.C) noreturn {
asm volatile ("la gp, __global_pointer$");
asm volatile ("mv sp, %[eos]"
:
: [eos] "r" (@as(u32, microzig.config.end_of_stack)),
);
root.initialize_system_memories();
asm volatile ("csrsi 0x804, 0b111"); // INTSYSCR: enable EABI + Interrupt nesting + HPE
asm volatile ("csrsi mtvec, 0b11"); // mtvec: absolute address + vector table mode
microzig.cpu.enable_interrupts();
microzig_main();
}
export fn _reset_vector() linksection("microzig_flash_start") callconv(.Naked) void {
asm volatile ("j _start");
}
};
pub fn export_startup_logic() void {
@export(startup_logic._start, .{ .name = "_start" });
}
const VectorTable = microzig.chip.VectorTable;
pub const vector_table: VectorTable = blk: {
var tmp: VectorTable = .{};
if (@hasDecl(root, "microzig_options")) {
for (@typeInfo(root.VectorTableOptions).Struct.fields) |field|
@field(tmp, field.name) = @field(root.microzig_options.interrupts, field.name);
}
break :blk tmp;
};

@ -0,0 +1,24 @@
const std = @import("std");
const mz = @import("microzig");
const periph = mz.chip.peripherals;
const RCC = periph.RCC;
const FLASH = periph.FLASH;
pub fn rcc_init_hsi_pll() void {
const CFG0_PLL_TRIM: *u8 = @ptrFromInt(0x1FFFF7D4); // Factory HSI clock trim value
if (CFG0_PLL_TRIM.* != 0xFF) {
RCC.CTLR.modify(.{ .HSITRIM = @as(u5, @truncate(CFG0_PLL_TRIM.*)) });
}
FLASH.ACTLR.modify(.{ .LATENCY = 1 }); // Flash wait state 1 for 48MHz clock
RCC.CFGR0.modify(.{
.PLLSRC = 0, // HSI
.HPRE = 0, // Prescaler off
});
RCC.CTLR.modify(.{ .PLLON = 1 });
while (RCC.CTLR.read().PLLRDY != 1) {}
RCC.CFGR0.modify(.{ .SW = 0b10 }); // Select PLL clock source
while (RCC.CFGR0.read().SWS != 0b10) {} // Spin until PLL selected
}

@ -23,6 +23,7 @@ const bsps = .{
.{ "bsp/stmicro/stm32", @import("bsp/stmicro/stm32") },
.{ "bsp/espressif/esp", @import("bsp/espressif/esp") },
.{ "bsp/raspberrypi/rp2040", @import("bsp/raspberrypi/rp2040") },
.{ "bsp/wch/ch32", @import("bsp/wch/ch32") },
};
pub fn build(b: *Build) void {

@ -1,6 +1,7 @@
.{
.name = "microzig",
.version = "0.12.1",
.version = "0.13.0",
.minimum_zig_version = "0.13.0",
.dependencies = .{
// packages within the monorepo so that others can reach them
.build = .{ .path = "build" },
@ -29,8 +30,8 @@
// used for creating package tarballs
.boxzer = .{
.url = "https://github.com/mattnite/boxzer/archive/74f17daa97f6861c31b30a5070136216c08eb39b.tar.gz",
.hash = "1220a14c01a66c023d8944dc672edd5121f98f82196fefbc09a13bcadb96e1c8e7f1",
.url = "https://github.com/mattnite/boxzer/archive/6bd6636d780f626af1c40a27be2680e223965c8a.tar.gz",
.hash = "1220432ca3323f0a7033fd84df6d0f2d66aecf4c5301b3ac70c96cca8b0938164f17",
},
},

@ -23,7 +23,7 @@ pub fn build(b: *Build) !void {
const uf2_dep = b.dependency("microzig/tools/uf2", .{});
const build_test = b.addTest(.{
.root_source_file = .{ .path = "build.zig" },
.root_source_file = b.path("build.zig"),
});
build_test.root_module.addAnonymousImport("uf2", .{
@ -39,6 +39,9 @@ pub fn build(b: *Build) !void {
b.getInstallStep().dependOn(&install_docs.step);
}
fn root() []const u8 {
return comptime (std.fs.path.dirname(@src().file) orelse ".");
}
/// Creates a new MicroZig build environment that can be used to create new firmware.
pub fn init(b: *Build, opts: struct {
dependency_name: []const u8 = "microzig/build",
@ -53,7 +56,7 @@ pub fn init(b: *Build, opts: struct {
.microzig_core = core_dep,
.generate_linkerscript = mz_dep.builder.addExecutable(.{
.name = "generate-linkerscript",
.root_source_file = .{ .path = "src/generate_linkerscript.zig" },
.root_source_file = .{ .cwd_relative = comptime root() ++ "/src/generate_linkerscript.zig" },
.target = mz_dep.builder.host,
}),
};

@ -4,7 +4,7 @@ const LazyPath = Build.LazyPath;
pub fn build(b: *Build) void {
_ = b.addModule("definitions", .{
.root_source_file = .{ .path = "build.zig" },
.root_source_file = b.path("build.zig"),
});
}

@ -18,8 +18,8 @@ pub fn build(b: *std.Build) !void {
pub const cpus = struct {
pub const avr5 = MicroZig.Cpu{
.name = "AVR5",
.root_source_file = .{ .path = build_root ++ "/src/cpus/avr5.zig" },
.target = std.zig.CrossTarget{
.root_source_file = .{ .cwd_relative = build_root ++ "/src/cpus/avr5.zig" },
.target = std.Target.Query{
.cpu_arch = .avr,
.cpu_model = .{ .explicit = &std.Target.avr.cpu.avr5 },
.os_tag = .freestanding,
@ -29,8 +29,8 @@ pub const cpus = struct {
pub const cortex_m0 = MicroZig.Cpu{
.name = "ARM Cortex-M0",
.root_source_file = .{ .path = build_root ++ "/src/cpus/cortex_m.zig" },
.target = std.zig.CrossTarget{
.root_source_file = .{ .cwd_relative = build_root ++ "/src/cpus/cortex_m.zig" },
.target = std.Target.Query{
.cpu_arch = .thumb,
.cpu_model = .{ .explicit = &std.Target.arm.cpu.cortex_m0 },
.os_tag = .freestanding,
@ -40,8 +40,8 @@ pub const cpus = struct {
pub const cortex_m0plus = MicroZig.Cpu{
.name = "ARM Cortex-M0+",
.root_source_file = .{ .path = build_root ++ "/src/cpus/cortex_m.zig" },
.target = std.zig.CrossTarget{
.root_source_file = .{ .cwd_relative = build_root ++ "/src/cpus/cortex_m.zig" },
.target = std.Target.Query{
.cpu_arch = .thumb,
.cpu_model = .{ .explicit = &std.Target.arm.cpu.cortex_m0plus },
.os_tag = .freestanding,
@ -51,8 +51,8 @@ pub const cpus = struct {
pub const cortex_m3 = MicroZig.Cpu{
.name = "ARM Cortex-M3",
.root_source_file = .{ .path = build_root ++ "/src/cpus/cortex_m.zig" },
.target = std.zig.CrossTarget{
.root_source_file = .{ .cwd_relative = build_root ++ "/src/cpus/cortex_m.zig" },
.target = std.Target.Query{
.cpu_arch = .thumb,
.cpu_model = .{ .explicit = &std.Target.arm.cpu.cortex_m3 },
.os_tag = .freestanding,
@ -62,8 +62,8 @@ pub const cpus = struct {
pub const cortex_m4 = MicroZig.Cpu{
.name = "ARM Cortex-M4",
.root_source_file = .{ .path = build_root ++ "/src/cpus/cortex_m.zig" },
.target = std.zig.CrossTarget{
.root_source_file = .{ .cwd_relative = build_root ++ "/src/cpus/cortex_m.zig" },
.target = std.Target.Query{
.cpu_arch = .thumb,
.cpu_model = .{ .explicit = &std.Target.arm.cpu.cortex_m4 },
.os_tag = .freestanding,
@ -71,10 +71,22 @@ pub const cpus = struct {
},
};
pub const cortex_m4f = MicroZig.Cpu{
.name = "ARM Cortex-M4F",
.root_source_file = .{ .cwd_relative = build_root ++ "/src/cpus/cortex_m.zig" },
.target = std.zig.CrossTarget{
.cpu_arch = .thumb,
.cpu_model = .{ .explicit = &std.Target.arm.cpu.cortex_m4 },
.cpu_features_add = std.Target.arm.featureSet(&.{.vfp4d16sp}),
.os_tag = .freestanding,
.abi = .eabihf,
},
};
pub const riscv32_imac = MicroZig.Cpu{
.name = "RISC-V 32-bit",
.root_source_file = .{ .path = build_root ++ "/src/cpus/riscv32.zig" },
.target = std.zig.CrossTarget{
.root_source_file = .{ .cwd_relative = build_root ++ "/src/cpus/riscv32.zig" },
.target = std.Target.Query{
.cpu_arch = .riscv32,
.cpu_model = .{ .explicit = &std.Target.riscv.cpu.sifive_e21 },
.os_tag = .freestanding,

@ -13,8 +13,21 @@
const std = @import("std");
const builtin = @import("builtin");
/// USB primitive types
pub const types = @import("usb/types.zig");
/// USB Human Interface Device (HID)
pub const hid = @import("usb/hid.zig");
pub const cdc = @import("usb/cdc.zig");
pub const vendor = @import("usb/vendor.zig");
pub const utils = @import("usb/utils.zig");
pub const templates = @import("usb/templates.zig");
const DescType = types.DescType;
const Dir = types.Dir;
const Endpoint = types.Endpoint;
const SetupRequest = types.SetupRequest;
const BosConfig = utils.BosConfig;
/// Create a USB device
///
@ -40,43 +53,21 @@ pub fn Usb(comptime f: anytype) type {
var usb_config: ?*DeviceConfiguration = null;
/// The clock has been initialized [Y/n]
var clk_init: bool = false;
var itf_to_drv: [16]u8 = .{0} ** 16;
var ep_to_drv: [4][2]u8 = .{.{0} ** 2} ** 4;
/// Index of enpoint buffer 0 out
pub const EP0_OUT_IDX = 0;
/// Index of enpoint buffer 0 in
pub const EP0_IN_IDX = 1;
/// The callbacks passed provided by the caller
pub const callbacks = f;
/// Initialize the USB clock
pub fn init_clk() void {
f.usb_init_clk();
clk_init = true;
}
/// Initialize the usb device using the given configuration
///
/// This function will return an error if the clock hasn't been initialized.
pub fn init_device(device_config: *DeviceConfiguration) !void {
if (!clk_init) return error.UninitializedClock;
f.usb_init_device(device_config);
usb_config = device_config;
}
/// Usb task function meant to be executed in regular intervals after
/// initializing the device.
///
/// This function will return an error if the device hasn't been initialized.
pub fn task(debug: bool) !void {
if (usb_config == null) return error.UninitializedDevice;
// We'll keep some state in Plain Old Static Local Variables:
const S = struct {
var debug_mode = false;
// When the host gives us a new address, we can't just slap it into
// registers right away, because we have to do an acknowledgement step using
// our _old_ address.
var new_address: ?u8 = null;
// 0 - no config set
var cfg_num: u16 = 0;
// Flag recording whether the host has configured us with a
// `SetConfiguration` message.
var configured = false;
@ -88,6 +79,10 @@ pub fn Usb(comptime f: anytype) type {
var tmp: [128]u8 = .{0} ** 128;
// Keeps track of sent data from tmp buffer
var buffer_reader = BufferReader { .buffer = &.{} };
// Last setup packet request
var setup_packet: types.SetupPacket = undefined;
// Class driver associated with last setup request if any
var driver: ?*types.UsbClassDriver = null;
};
// Command endpoint utilities
@ -95,88 +90,147 @@ pub fn Usb(comptime f: anytype) type {
/// Command response utility function that can split long data in multiple packets
fn send_cmd_response(data: []const u8, expected_max_length: u16) void {
const cmd_in_endpoint = usb_config.?.endpoints[EP0_IN_IDX];
S.buffer_reader = BufferReader { .buffer = data[0..@min(data.len, expected_max_length)] };
const data_chunk = S.buffer_reader.try_peek(cmd_in_endpoint.descriptor.max_packet_size);
const data_chunk = S.buffer_reader.try_peek(64);
if (data_chunk.len > 0) {
f.usb_start_tx(
cmd_in_endpoint,
data_chunk
);
f.usb_start_tx(Endpoint.EP0_IN_IDX, data_chunk);
}
}
fn send_cmd_ack() void {
f.usb_start_tx(Endpoint.EP0_IN_IDX, &.{});
}
};
// Check which interrupt flags are set.
const ints = f.get_interrupts();
/// Initialize the USB clock
pub fn init_clk() void {
f.usb_init_clk();
clk_init = true;
}
// Setup request received?
if (ints.SetupReq) {
if (debug) std.log.info("setup req", .{});
/// Initialize the usb device using the given configuration
///
/// This function will return an error if the clock hasn't been initialized.
pub fn init_device(device_config: *DeviceConfiguration) !void {
if (!clk_init) return error.UninitializedClock;
// Get the setup request setup packet
f.usb_init_device(device_config);
usb_config = device_config;
const device_interface = device();
for (usb_config.?.drivers) |*driver| {
driver.init(device_interface);
}
}
fn device() types.UsbDevice {
return .{
.fn_ready = device_ready,
.fn_control_transfer = device_control_transfer,
.fn_control_ack = device_control_ack,
.fn_endpoint_open = device_endpoint_open,
.fn_endpoint_transfer = device_endpoint_transfer
};
}
fn device_ready() bool {
return S.started;
}
fn device_control_transfer(setup: *const types.SetupPacket, data: []const u8) void {
CmdEndpoint.send_cmd_response(data, setup.length);
}
fn device_control_ack(_: *const types.SetupPacket) void {
CmdEndpoint.send_cmd_ack();
}
fn device_endpoint_open(ep_desc: []const u8) void {
const ep_addr = BosConfig.get_data_u8(ep_desc, 2);
const ep_transfer_type = BosConfig.get_data_u8(ep_desc, 3);
const ep_max_packet_size = BosConfig.get_data_u16(ep_desc, 4);
f.endpoint_init(ep_addr, ep_max_packet_size, types.TransferType.from_u8(ep_transfer_type) orelse types.TransferType.Bulk);
}
fn device_endpoint_transfer(ep_addr: u8, data: []const u8) void {
f.usb_start_tx(ep_addr, data);
}
fn get_driver(drv_idx: u8) *types.UsbClassDriver {
return &usb_config.?.drivers[drv_idx];
}
fn get_setup_packet() types.SetupPacket {
const setup = f.get_setup_packet();
S.setup_packet = setup;
S.driver = null;
return setup;
}
// Reset PID to 1 for EP0 IN. Every DATA packet we send in response
// to an IN on EP0 needs to use PID DATA1, and this line will ensure
// that.
usb_config.?.endpoints[EP0_IN_IDX].next_pid_1 = true;
/// Usb task function meant to be executed in regular intervals after
/// initializing the device.
///
/// This function will return an error if the device hasn't been initialized.
pub fn task(debug: bool) !void {
if (usb_config == null) return error.UninitializedDevice;
// Attempt to parse the request type and request into one of our
// known enum values, and then inspect them. (These will return None
// if we get an unexpected numeric value.)
const reqty = Dir.of_endpoint_addr(setup.request_type);
const req = SetupRequest.from_u8(setup.request);
S.debug_mode = debug;
if (reqty == Dir.Out and req != null and req.? == SetupRequest.SetAddress) {
// The new address is in the bottom 8 bits of the setup
// packet value field. Store it for use later.
// Device Specific Request
const DeviceRequestProcessor = struct {
fn process_setup_request(setup: *const types.SetupPacket) !void {
switch (setup.request_type.type) {
.Class => {
//const itfIndex = setup.index & 0x00ff;
std.log.info("Device.Class", .{});
},
.Standard => {
const req = SetupRequest.from_u8(setup.request);
if (req == null) return;
switch (req.?) {
SetupRequest.SetAddress => {
S.new_address = @as(u8, @intCast(setup.value & 0xff));
// The address will actually get set later, we have
// to use address 0 to send a status response.
f.usb_start_tx(
usb_config.?.endpoints[EP0_IN_IDX], //EP0_IN_CFG,
&.{}, // <- see, empty buffer
);
if (debug) std.log.info(" SetAddress: {}", .{S.new_address.?});
} else if (reqty == Dir.Out and req != null and req.? == SetupRequest.SetConfiguration) {
// We only have one configuration, and it doesn't really
// mean anything to us -- more of a formality. All we do in
// response to this is:
CmdEndpoint.send_cmd_ack();
if (S.debug_mode) std.log.info(" SetAddress: {}", .{S.new_address.?});
},
SetupRequest.SetConfiguration => {
if (S.debug_mode) std.log.info(" SetConfiguration", .{});
const cfg_num = setup.value;
if (S.cfg_num != cfg_num) {
if (S.cfg_num > 0) {
// TODO - cleanup current config drivers
}
if (cfg_num > 0) {
try process_set_config(cfg_num - 1);
// TODO: call mount callback if any
} else {
// TODO: call umount callback if any
}
}
S.cfg_num = cfg_num;
S.configured = true;
f.usb_start_tx(
usb_config.?.endpoints[EP0_IN_IDX], //EP0_IN_CFG,
&.{}, // <- see, empty buffer
);
if (debug) std.log.info(" SetConfiguration", .{});
} else if (reqty == Dir.Out) {
// This is sort of a hack, but: if we get any other kind of
// OUT, just acknowledge it with the same zero-length status
// phase that we use for control transfers that we _do_
// understand. This keeps the host from spinning forever
// while we NAK.
//
// This behavior copied shamelessly from the C example.
f.usb_start_tx(
usb_config.?.endpoints[EP0_IN_IDX], // EP0_IN_CFG,
&.{}, // <- see, empty buffer
);
if (debug) std.log.info(" Just OUT", .{});
} else if (reqty == Dir.In and req != null and req.? == SetupRequest.GetDescriptor) {
// Identify the requested descriptor type, which is in the
// _top_ 8 bits of value.
const descriptor_type = DescType.from_u16(setup.value >> 8);
if (debug) std.log.info(" GetDescriptor: {}", .{setup.value >> 8});
CmdEndpoint.send_cmd_ack();
},
SetupRequest.GetDescriptor => {
const descriptor_type = DescType.from_u8(@intCast(setup.value >> 8));
if (descriptor_type) |dt| {
switch (dt) {
try process_get_descriptor(setup, dt);
}
}
}
},
else => {}
}
}
fn process_get_descriptor(setup: *const types.SetupPacket, descriptor_type: DescType) !void {
switch (descriptor_type) {
.Device => {
if (debug) std.log.info(" Device", .{});
// TODO: this sure looks like a duplicate, but it's
// a duplicate that was present in the C
// implementation.
usb_config.?.endpoints[EP0_IN_IDX].next_pid_1 = true;
if (S.debug_mode) std.log.info(" Device", .{});
var bw = BufferWriter { .buffer = &S.tmp };
try bw.write(&usb_config.?.device_descriptor.serialize());
@ -184,33 +238,15 @@ pub fn Usb(comptime f: anytype) type {
CmdEndpoint.send_cmd_response(bw.get_written_slice(), setup.length);
},
.Config => {
if (debug) std.log.info(" Config", .{});
if (S.debug_mode) std.log.info(" Config", .{});
// Config descriptor requests are slightly unusual.
// We can respond with just our config descriptor,
// but we can _also_ append our interface and
// endpoint descriptors to the end, saving some
// round trips.
var bw = BufferWriter { .buffer = &S.tmp };
try bw.write(&usb_config.?.config_descriptor.serialize());
try bw.write(&usb_config.?.interface_descriptor.serialize());
// Seems like the host does not bother asking for the
// hid descriptor so we'll just send it with the
// other descriptors.
if (usb_config.?.hid) |hid_conf| {
try bw.write(&hid_conf.hid_descriptor.serialize());
}
for (usb_config.?.endpoints[2..]) |ep| {
try bw.write(&ep.descriptor.serialize());
}
try bw.write(usb_config.?.config_descriptor);
CmdEndpoint.send_cmd_response(bw.get_written_slice(), setup.length);
},
.String => {
if (debug) std.log.info(" String", .{});
if (S.debug_mode) std.log.info(" String", .{});
// String descriptor index is in bottom 8 bits of
// `value`.
const i: usize = @intCast(setup.value & 0xff);
@ -236,26 +272,16 @@ pub fn Usb(comptime f: anytype) type {
CmdEndpoint.send_cmd_response(bytes, setup.length);
},
.Interface => {
if (debug) std.log.info(" Interface", .{});
// We don't expect the host to send this because we
// delivered our interface descriptor with the
// config descriptor.
//
// Should probably implement it, though, because
// otherwise the host will be unhappy. TODO.
//
// Note that the C example gets away with ignoring
// this.
if (S.debug_mode) std.log.info(" Interface", .{});
},
.Endpoint => {
if (debug) std.log.info(" Endpoint", .{});
// Same deal as interface descriptors above.
if (S.debug_mode) std.log.info(" Endpoint", .{});
},
.DeviceQualifier => {
if (debug) std.log.info(" DeviceQualifier", .{});
if (S.debug_mode) std.log.info(" DeviceQualifier", .{});
// We will just copy parts of the DeviceDescriptor because
// the DeviceQualifierDescriptor can be seen as a subset.
const dqd = DeviceQualifierDescriptor{
const dqd = types.DeviceQualifierDescriptor{
.bcd_usb = usb_config.?.device_descriptor.bcd_usb,
.device_class = usb_config.?.device_descriptor.device_class,
.device_subclass = usb_config.?.device_descriptor.device_subclass,
@ -269,51 +295,107 @@ pub fn Usb(comptime f: anytype) type {
CmdEndpoint.send_cmd_response(bw.get_written_slice(), setup.length);
},
else => {}
}
}
fn process_set_config(_: u16) !void {
// TODO: we support just one config for now so ignore config index
const bos_cfg = usb_config.?.config_descriptor;
var curr_bos_cfg = bos_cfg;
var curr_drv_idx: u8 = 0;
if (BosConfig.try_get_desc_as(types.ConfigurationDescriptor, curr_bos_cfg)) |_| {
curr_bos_cfg = BosConfig.get_desc_next(curr_bos_cfg);
} else {
// Maybe the unknown request type is a hid request
// TODO - error
return;
}
if (usb_config.?.hid) |hid_conf| {
const _hid_desc_type = hid.DescType.from_u16(setup.value >> 8);
while (curr_bos_cfg.len > 0) : (curr_drv_idx += 1) {
var assoc_itf_count: u8 = 1;
// New class starts optionally from InterfaceAssociation followed by mandatory Interface
if (BosConfig.try_get_desc_as(types.InterfaceAssociationDescriptor, curr_bos_cfg)) |desc_assoc_itf| {
assoc_itf_count = desc_assoc_itf.interface_count;
curr_bos_cfg = BosConfig.get_desc_next(curr_bos_cfg);
}
if (_hid_desc_type) |hid_desc_type| {
switch (hid_desc_type) {
.Hid => {
if (debug) std.log.info(" HID", .{});
if (BosConfig.get_desc_type(curr_bos_cfg) != DescType.Interface) {
// TODO - error
return;
}
const desc_itf = BosConfig.get_desc_as(types.InterfaceDescriptor, curr_bos_cfg);
var bw = BufferWriter { .buffer = &S.tmp };
try bw.write(&hid_conf.hid_descriptor.serialize());
var driver = usb_config.?.drivers[curr_drv_idx];
const drv_cfg_len = try driver.open(curr_bos_cfg);
CmdEndpoint.send_cmd_response(bw.get_written_slice(), setup.length);
},
.Report => {
if (debug) std.log.info(" Report", .{});
for (0..assoc_itf_count) |itf_offset| {
const itf_num = desc_itf.interface_number + itf_offset;
itf_to_drv[itf_num] = curr_drv_idx;
}
// The report descriptor is already a (static)
// u8 array, i.e., we can pass it directly
CmdEndpoint.send_cmd_response(hid_conf.report_descriptor, setup.length);
},
.Physical => {
if (debug) std.log.info(" Physical", .{});
// Ignore for now
},
bind_endpoints_to_driver(curr_bos_cfg[0..drv_cfg_len], curr_drv_idx);
curr_bos_cfg = curr_bos_cfg[drv_cfg_len..];
// TODO: TMP solution - just 1 driver so quit while loop
return;
}
} else {
// It's not a valid HID request. This can totally happen
// we'll just ignore it for now...
}
fn bind_endpoints_to_driver(drv_bos_cfg: []const u8, drv_idx: u8) void {
var curr_bos_cfg = drv_bos_cfg;
while (curr_bos_cfg.len > 0) : ({curr_bos_cfg = BosConfig.get_desc_next(curr_bos_cfg);}) {
if (BosConfig.try_get_desc_as(types.EndpointDescriptor, curr_bos_cfg)) |desc_ep| {
const ep_addr = desc_ep.endpoint_address;
ep_to_drv[Endpoint.num_from_address(ep_addr)][Endpoint.dir_from_address(ep_addr).as_number()] = drv_idx;
}
}
} else if (reqty == Dir.In) {
if (debug) std.log.info(" Just IN", .{});
// Other IN request. Ignore.
} else {
if (debug) std.log.info(" This is unexpected", .{});
// Unexpected request type or request bits. This can totally
// happen (yay, hardware!) but is rare in practice. Ignore
// it.
}
} // <-- END of setup request handling
};
// Class/Interface Specific Request
const InterfaceRequestProcessor = struct {
fn process_setup_request(setup: *const types.SetupPacket) !void {
const itf: u8 = @intCast(setup.index & 0xFF);
var driver = get_driver(itf_to_drv[itf]);
S.driver = driver;
if (driver.class_control(.Setup, setup) == false) {
// TODO
}
}
};
// Endpoint Specific Request
const EndpointRequestProcessor = struct {
fn process_setup_request(_: *const types.SetupPacket) !void {
}
};
// Check which interrupt flags are set.
const ints = f.get_interrupts();
// Setup request received?
if (ints.SetupReq) {
if (debug) std.log.info("setup req", .{});
const setup = get_setup_packet();
// Reset PID to 1 for EP0 IN. Every DATA packet we send in response
// to an IN on EP0 needs to use PID DATA1, and this line will ensure
// that.
// TODO - maybe it can be moved to f.get_setup_packet?
f.reset_ep0();
switch (setup.request_type.recipient) {
.Device => try DeviceRequestProcessor.process_setup_request(&setup),
.Interface => try InterfaceRequestProcessor.process_setup_request(&setup),
.Endpoint => try EndpointRequestProcessor.process_setup_request(&setup),
else => {}
}
}
// Events on one or more buffers? (In practice, always one.)
if (ints.BuffStatus) {
@ -326,11 +408,10 @@ pub fn Usb(comptime f: anytype) type {
// Perform any required action on the data. For OUT, the `data`
// will be whatever was sent by the host. For IN, it's a copy of
// whatever we sent.
switch (epb.endpoint.descriptor.endpoint_address) {
EP0_IN_ADDR => {
switch (epb.endpoint_address) {
Endpoint.EP0_IN_ADDR => {
if (debug) std.log.info(" EP0_IN_ADDR", .{});
const cmd_in_endpoint = usb_config.?.endpoints[EP0_IN_IDX];
const buffer_reader = &S.buffer_reader;
// We use this opportunity to finish the delayed
@ -342,17 +423,21 @@ pub fn Usb(comptime f: anytype) type {
if (epb.buffer.len > 0 and buffer_reader.get_remaining_bytes_count() > 0) {
_ = buffer_reader.try_advance(epb.buffer.len);
const next_data_chunk = buffer_reader.try_read(cmd_in_endpoint.descriptor.max_packet_size);
const next_data_chunk = buffer_reader.try_peek(64);
if (next_data_chunk.len > 0) {
f.usb_start_tx(
cmd_in_endpoint,
Endpoint.EP0_IN_IDX,
next_data_chunk,
);
} else {
f.usb_start_rx(
usb_config.?.endpoints[EP0_OUT_IDX], // EP0_OUT_CFG,
Endpoint.EP0_OUT_IDX,
0,
);
if (S.driver) |driver| {
_ = driver.class_control(.Ack, &S.setup_packet);
}
}
} else {
// Otherwise, we've just finished sending
@ -361,19 +446,19 @@ pub fn Usb(comptime f: anytype) type {
// OUT) a zero-byte DATA packet, so, set that
// up:
f.usb_start_rx(
usb_config.?.endpoints[EP0_OUT_IDX], // EP0_OUT_CFG,
Endpoint.EP0_OUT_IDX,
0,
);
if (S.driver) |driver| {
_ = driver.class_control(.Ack, &S.setup_packet);
}
}
},
else => {
if (debug) std.log.info(" ELSE, ep_addr: {}", .{
epb.endpoint.descriptor.endpoint_address & 0x7f,
epb.endpoint_address & 0x7f,
});
// Handle user provided endpoints.
// Invoke the callback (if the user provides one).
if (epb.endpoint.callback) |callback| callback(usb_config.?, epb.buffer);
},
}
}
@ -396,376 +481,22 @@ pub fn Usb(comptime f: anytype) type {
// If we have been configured but haven't reached this point yet, set up
// our custom EP OUT's to receive whatever data the host wants to send.
if (S.configured and !S.started) {
// We can skip the first two endpoints because those are EP0_OUT and EP0_IN
for (usb_config.?.endpoints[2..]) |ep| {
if (Dir.of_endpoint_addr(ep.descriptor.endpoint_address) == .Out) {
// Hey host! we expect data!
f.usb_start_rx(
ep,
64,
);
}
}
S.started = true;
}
}
};
}
// +++++++++++++++++++++++++++++++++++++++++++++++++
// Data Types
// +++++++++++++++++++++++++++++++++++++++++++++++++
// -------------------------
// | DeviceDescriptor |
// -------------------------
// |
// v
// -------------------------
// | ConfigurationDesc |
// -------------------------
// |
// v
// -------------------------
// | InterfaceDescriptor |
// -------------------------
// | |
// v ------------------------------
// ------------------------- |
// | EndpointDescriptor | v
// ------------------------- ---------------------
// | HID Descriptor |
// ---------------------
/// Types of USB descriptor
pub const DescType = enum(u8) {
Device = 0x01,
Config = 0x02,
String = 0x03,
Interface = 0x04,
Endpoint = 0x05,
DeviceQualifier = 0x06,
//-------- Class Specific Descriptors ----------
// 0x21 ...
pub fn from_u16(v: u16) ?@This() {
return switch (v) {
1 => @This().Device,
2 => @This().Config,
3 => @This().String,
4 => @This().Interface,
5 => @This().Endpoint,
6 => @This().DeviceQualifier,
else => null,
};
}
};
/// Types of transfer that can be indicated by the `attributes` field on
/// `EndpointDescriptor`.
pub const TransferType = enum(u2) {
Control = 0,
Isochronous = 1,
Bulk = 2,
Interrupt = 3,
};
/// The types of USB SETUP requests that we understand.
pub const SetupRequest = enum(u8) {
/// Asks the device to send a certain descriptor back to the host. Always
/// used on an IN request.
GetDescriptor = 0x06,
/// Notifies the device that it's being moved to a different address on the
/// bus. Always an OUT.
SetAddress = 0x05,
/// Configures a device by choosing one of the options listed in its
/// descriptors. Always an OUT.
SetConfiguration = 0x09,
pub fn from_u8(request: u8) ?@This() {
return switch (request) {
0x06 => SetupRequest.GetDescriptor,
0x05 => SetupRequest.SetAddress,
0x09 => SetupRequest.SetConfiguration,
else => null,
};
}
};
/// USB deals in two different transfer directions, called OUT (host-to-device)
/// and IN (device-to-host). In the vast majority of cases, OUT is represented
/// by a 0 byte, and IN by an `0x80` byte.
pub const Dir = enum(u8) {
Out = 0,
In = 0x80,
pub inline fn endpoint(self: @This(), num: u8) u8 {
return num | @intFromEnum(self);
}
pub inline fn of_endpoint_addr(addr: u8) @This() {
return if (addr & @intFromEnum(@This().In) != 0) @This().In else @This().Out;
}
};
/// Describes an endpoint within an interface
pub const EndpointDescriptor = struct {
/// Type of this descriptor, must be `Endpoint`.
descriptor_type: DescType,
/// Address of this endpoint, where the bottom 4 bits give the endpoint
/// number (0..15) and the top bit distinguishes IN (1) from OUT (0).
endpoint_address: u8,
/// Endpoint attributes; the most relevant part is the bottom 2 bits, which
/// control the transfer type using the values from `TransferType`.
attributes: u8,
/// Maximum packet size this endpoint can accept/produce.
max_packet_size: u16,
/// Interval for polling interrupt/isochronous endpoints (which we don't
/// currently support) in milliseconds.
interval: u8,
pub fn serialize(self: *const @This()) [7]u8 {
var out: [7]u8 = undefined;
out[0] = out.len;
out[1] = @intFromEnum(self.descriptor_type);
out[2] = self.endpoint_address;
out[3] = self.attributes;
out[4] = @intCast(self.max_packet_size & 0xff);
out[5] = @intCast((self.max_packet_size >> 8) & 0xff);
out[6] = self.interval;
return out;
}
};
/// Description of an interface within a configuration.
pub const InterfaceDescriptor = struct {
/// Type of this descriptor, must be `Interface`.
descriptor_type: DescType,
/// ID of this interface.
interface_number: u8,
/// Allows a single `interface_number` to have several alternate interface
/// settings, where each alternate increments this field. Normally there's
/// only one, and `alternate_setting` is zero.
alternate_setting: u8,
/// Number of endpoint descriptors in this interface.
num_endpoints: u8,
/// Interface class code, distinguishing the type of interface.
interface_class: u8,
/// Interface subclass code, refining the class of interface.
interface_subclass: u8,
/// Protocol within the interface class/subclass.
interface_protocol: u8,
/// Index of interface name within string descriptor table.
interface_s: u8,
pub fn serialize(self: *const @This()) [9]u8 {
var out: [9]u8 = undefined;
out[0] = out.len;
out[1] = @intFromEnum(self.descriptor_type);
out[2] = self.interface_number;
out[3] = self.alternate_setting;
out[4] = self.num_endpoints;
out[5] = self.interface_class;
out[6] = self.interface_subclass;
out[7] = self.interface_protocol;
out[8] = self.interface_s;
return out;
}
};
/// Description of a single available device configuration.
pub const ConfigurationDescriptor = struct {
/// Type of this descriptor, must be `Config`.
descriptor_type: DescType,
/// Total length of all descriptors in this configuration, concatenated.
/// This will include this descriptor, plus at least one interface
/// descriptor, plus each interface descriptor's endpoint descriptors.
total_length: u16,
/// Number of interface descriptors in this configuration.
num_interfaces: u8,
/// Number to use when requesting this configuration via a
/// `SetConfiguration` request.
configuration_value: u8,
/// Index of this configuration's name in the string descriptor table.
configuration_s: u8,
/// Bit set of device attributes:
///
/// - Bit 7 should be set (indicates that device can be bus powered in USB
/// 1.0).
/// - Bit 6 indicates that the device can be self-powered.
/// - Bit 5 indicates that the device can signal remote wakeup of the host
/// (like a keyboard).
/// - The rest are reserved and should be zero.
attributes: u8,
/// Maximum device power consumption in units of 2mA.
max_power: u8,
pub fn serialize(self: *const @This()) [9]u8 {
var out: [9]u8 = undefined;
out[0] = out.len;
out[1] = @intFromEnum(self.descriptor_type);
out[2] = @intCast(self.total_length & 0xff);
out[3] = @intCast((self.total_length >> 8) & 0xff);
out[4] = self.num_interfaces;
out[5] = self.configuration_value;
out[6] = self.configuration_s;
out[7] = self.attributes;
out[8] = self.max_power;
return out;
}
};
/// Describes a device. This is the most broad description in USB and is
/// typically the first thing the host asks for.
pub const DeviceDescriptor = struct {
/// Type of this descriptor, must be `Device`.
descriptor_type: DescType,
/// Version of the device descriptor / USB protocol, in binary-coded
/// decimal. This is typically `0x01_10` for USB 1.1.
bcd_usb: u16,
/// Class of device, giving a broad functional area.
device_class: u8,
/// Subclass of device, refining the class.
device_subclass: u8,
/// Protocol within the subclass.
device_protocol: u8,
/// Maximum unit of data this device can move.
max_packet_size0: u8,
/// ID of product vendor.
vendor: u16,
/// ID of product.
product: u16,
/// Device version number, as BCD again.
bcd_device: u16,
/// Index of manufacturer name in string descriptor table.
manufacturer_s: u8,
/// Index of product name in string descriptor table.
product_s: u8,
/// Index of serial number in string descriptor table.
serial_s: u8,
/// Number of configurations supported by this device.
num_configurations: u8,
pub fn serialize(self: *const @This()) [18]u8 {
var out: [18]u8 = undefined;
out[0] = out.len;
out[1] = @intFromEnum(self.descriptor_type);
out[2] = @intCast(self.bcd_usb & 0xff);
out[3] = @intCast((self.bcd_usb >> 8) & 0xff);
out[4] = self.device_class;
out[5] = self.device_subclass;
out[6] = self.device_protocol;
out[7] = self.max_packet_size0;
out[8] = @intCast(self.vendor & 0xff);
out[9] = @intCast((self.vendor >> 8) & 0xff);
out[10] = @intCast(self.product & 0xff);
out[11] = @intCast((self.product >> 8) & 0xff);
out[12] = @intCast(self.bcd_device & 0xff);
out[13] = @intCast((self.bcd_device >> 8) & 0xff);
out[14] = self.manufacturer_s;
out[15] = self.product_s;
out[16] = self.serial_s;
out[17] = self.num_configurations;
return out;
}
};
/// USB Device Qualifier Descriptor
/// This descriptor is mostly the same as the DeviceDescriptor
pub const DeviceQualifierDescriptor = struct {
/// Type of this descriptor, must be `Device`.
descriptor_type: DescType = DescType.DeviceQualifier,
/// Version of the device descriptor / USB protocol, in binary-coded
/// decimal. This is typically `0x01_10` for USB 1.1.
bcd_usb: u16,
/// Class of device, giving a broad functional area.
device_class: u8,
/// Subclass of device, refining the class.
device_subclass: u8,
/// Protocol within the subclass.
device_protocol: u8,
/// Maximum unit of data this device can move.
max_packet_size0: u8,
/// Number of configurations supported by this device.
num_configurations: u8,
/// Reserved for future use; must be 0
reserved: u8 = 0,
pub fn serialize(self: *const @This()) [10]u8 {
var out: [10]u8 = undefined;
out[0] = out.len;
out[1] = @intFromEnum(self.descriptor_type);
out[2] = @intCast(self.bcd_usb & 0xff);
out[3] = @intCast((self.bcd_usb >> 8) & 0xff);
out[4] = self.device_class;
out[5] = self.device_subclass;
out[6] = self.device_protocol;
out[7] = self.max_packet_size0;
out[8] = self.num_configurations;
out[9] = self.reserved;
return out;
}
};
/// Layout of an 8-byte USB SETUP packet.
pub const SetupPacket = extern struct {
request_type: u8,
/// Request. Standard setup requests are in the `SetupRequest` enum.
/// Devices can extend this with additional types as long as they don't
/// conflict.
request: u8,
/// A simple argument of up to 16 bits, specific to the request.
value: u16,
/// Not used in the requests we support.
index: u16,
/// If data will be transferred after this request (in the direction given
/// by `request_type`), this gives the number of bytes (OUT) or maximum
/// number of bytes (IN).
length: u16,
};
// +++++++++++++++++++++++++++++++++++++++++++++++++
// Driver support stuctures
// +++++++++++++++++++++++++++++++++++++++++++++++++
pub const EndpointConfiguration = struct {
descriptor: *const EndpointDescriptor,
/// Index of this endpoint's control register in the `ep_control` array.
///
/// TODO: this can be derived from the endpoint address, perhaps it should
/// be.
endpoint_control_index: ?usize,
/// Index of this endpoint's buffer control register in the
/// `ep_buffer_control` array.
///
/// TODO this, too, can be derived.
buffer_control_index: usize,
/// Index of this endpoint's data buffer in the array of data buffers
/// allocated from DPRAM. This can be arbitrary, and endpoints can even
/// share buffers if you're careful.
data_buffer_index: usize,
/// Keeps track of which DATA PID (DATA0/DATA1) is expected on this endpoint
/// next. If `true`, we're expecting `DATA1`, otherwise `DATA0`.
next_pid_1: bool,
/// Optional callback for custom OUT endpoints. This function will be called
/// if the device receives data on the corresponding endpoint.
callback: ?*const fn (dc: *DeviceConfiguration, data: []const u8) void = null,
};
pub const DeviceConfiguration = struct {
device_descriptor: *const DeviceDescriptor,
interface_descriptor: *const InterfaceDescriptor,
config_descriptor: *const ConfigurationDescriptor,
device_descriptor: *const types.DeviceDescriptor,
config_descriptor: []const u8,
lang_descriptor: []const u8,
descriptor_strings: []const []const u8,
hid: ?struct {
hid_descriptor: *const hid.HidDescriptor,
report_descriptor: []const u8,
} = null,
endpoints: [4]*EndpointConfiguration,
drivers: []types.UsbClassDriver
};
/// Buffer pointers, once they're prepared and initialized.
@ -788,13 +519,6 @@ pub const Buffers = struct {
}
};
// Handy constants for the endpoints we use here
pub const EP0_IN_ADDR: u8 = Dir.In.endpoint(0);
pub const EP0_OUT_ADDR: u8 = Dir.Out.endpoint(0);
const EP1_OUT_ADDR: u8 = Dir.Out.endpoint(1);
const EP1_IN_ADDR: u8 = Dir.In.endpoint(1);
const EP2_IN_ADDR: u8 = Dir.In.endpoint(2);
/// USB interrupt status
///
/// __Note__: Available interrupts may change from device to device.
@ -822,7 +546,7 @@ pub const EPBError = error{
/// Element returned by the endpoint buffer iterator (EPBIter)
pub const EPB = struct {
/// The endpoint the data belongs to
endpoint: *EndpointConfiguration,
endpoint_address: u8,
/// Data buffer
buffer: []u8,
};
@ -927,8 +651,9 @@ const BufferReader = struct {
}
};
pub const UsbUtils = struct {
/// Convert an utf8 into an utf16 (little endian) string
pub fn utf8Toutf16Le(comptime s: []const u8) [s.len << 1]u8 {
pub fn utf8ToUtf16Le(comptime s: []const u8) [s.len << 1]u8 {
const l = s.len << 1;
var ret: [l]u8 = .{0} ** l;
var i: usize = 0;
@ -937,12 +662,13 @@ pub fn utf8Toutf16Le(comptime s: []const u8) [s.len << 1]u8 {
}
return ret;
}
};
test "tests" {
_ = hid;
}
test "utf8 to utf16" {
try std.testing.expectEqualSlices(u8, "M\x00y\x00 \x00V\x00e\x00n\x00d\x00o\x00r\x00", &utf8Toutf16Le("My Vendor"));
try std.testing.expectEqualSlices(u8, "R\x00a\x00s\x00p\x00b\x00e\x00r\x00r\x00y\x00 \x00P\x00i\x00", &utf8Toutf16Le("Raspberry Pi"));
try std.testing.expectEqualSlices(u8, "M\x00y\x00 \x00V\x00e\x00n\x00d\x00o\x00r\x00", &UsbUtils.utf8Toutf16Le("My Vendor"));
try std.testing.expectEqualSlices(u8, "R\x00a\x00s\x00p\x00b\x00e\x00r\x00r\x00y\x00 \x00P\x00i\x00", &UsbUtils.utf8Toutf16Le("Raspberry Pi"));
}

@ -0,0 +1,254 @@
const std = @import("std");
const types = @import("types.zig");
const utils = @import("utils.zig");
const DescType = types.DescType;
const bos = utils.BosConfig;
pub const DescSubType = enum(u8) {
Header = 0x00,
CallManagement = 0x01,
ACM = 0x02,
Union = 0x06,
pub fn from_u16(v: u16) ?@This() {
return std.meta.intToEnum(@This(), v) catch null;
}
};
pub const CdcManagementRequestType = enum(u8) {
SetLineCoding = 0x20,
GetLineCoding = 0x21,
SetControlLineState = 0x22,
SendBreak = 0x23,
pub fn from_u8(v: u8) ?@This() {
return std.meta.intToEnum(@This(), v) catch null;
}
};
pub const CdcCommSubClassType = enum(u8) {
AbstractControlModel = 2
};
pub const CdcHeaderDescriptor = extern struct {
length: u8 = 5,
// Type of this descriptor, must be `ClassSpecific`.
descriptor_type: DescType = DescType.CsInterface,
// Subtype of this descriptor, must be `Header`.
descriptor_subtype: DescSubType = DescSubType.Header,
// USB Class Definitions for Communication Devices Specification release
// number in binary-coded decimal. Typically 0x01_10.
bcd_cdc: u16 align(1),
pub fn serialize(self: *const @This()) [5]u8 {
var out: [5]u8 = undefined;
out[0] = out.len;
out[1] = @intFromEnum(self.descriptor_type);
out[2] = @intFromEnum(self.descriptor_subtype);
out[3] = @intCast(self.bcd_cdc & 0xff);
out[4] = @intCast((self.bcd_cdc >> 8) & 0xff);
return out;
}
};
pub const CdcCallManagementDescriptor = extern struct {
length: u8 = 5,
// Type of this descriptor, must be `ClassSpecific`.
descriptor_type: DescType = DescType.CsInterface,
// Subtype of this descriptor, must be `CallManagement`.
descriptor_subtype: DescSubType = DescSubType.CallManagement,
// Capabilities. Should be 0x00 for use as a serial device.
capabilities: u8,
// Data interface number.
data_interface: u8,
pub fn serialize(self: *const @This()) [5]u8 {
var out: [5]u8 = undefined;
out[0] = out.len;
out[1] = @intFromEnum(self.descriptor_type);
out[2] = @intFromEnum(self.descriptor_subtype);
out[3] = self.capabilities;
out[4] = self.data_interface;
return out;
}
};
pub const CdcAcmDescriptor = extern struct {
length: u8 = 4,
// Type of this descriptor, must be `ClassSpecific`.
descriptor_type: DescType = DescType.CsInterface,
// Subtype of this descriptor, must be `ACM`.
descriptor_subtype: DescSubType = DescSubType.ACM,
// Capabilities. Should be 0x02 for use as a serial device.
capabilities: u8,
pub fn serialize(self: *const @This()) [4]u8 {
var out: [4]u8 = undefined;
out[0] = out.len;
out[1] = @intFromEnum(self.descriptor_type);
out[2] = @intFromEnum(self.descriptor_subtype);
out[3] = self.capabilities;
return out;
}
};
pub const CdcUnionDescriptor = extern struct {
length: u8 = 5,
// Type of this descriptor, must be `ClassSpecific`.
descriptor_type: DescType = DescType.CsInterface,
// Subtype of this descriptor, must be `Union`.
descriptor_subtype: DescSubType = DescSubType.Union,
// The interface number of the communication or data class interface
// designated as the master or controlling interface for the union.
master_interface: u8,
// The interface number of the first slave or associated interface in the
// union.
slave_interface_0: u8,
pub fn serialize(self: *const @This()) [5]u8 {
var out: [5]u8 = undefined;
out[0] = out.len;
out[1] = @intFromEnum(self.descriptor_type);
out[2] = @intFromEnum(self.descriptor_subtype);
out[3] = self.master_interface;
out[4] = self.slave_interface_0;
return out;
}
};
pub const CdcLineCoding = extern struct {
bit_rate: u32 align(1),
stop_bits: u8,
parity: u8,
data_bits: u8,
};
pub const CdcClassDriver = struct {
device: ?types.UsbDevice = null,
ep_notif: u8 = 0,
ep_in: u8 = 0,
ep_out: u8 = 0,
line_coding: CdcLineCoding = undefined,
pub fn write(self: *@This(), data: []const u8) void {
// TODO - ugly hack, current limitation 63 chars (in future endpoints should implement ring buffers)
const max_size = 63;
var buf: [64]u8 = undefined;
const size = @min(data.len, max_size);
@memcpy(buf[0..size], data[0..size]);
buf[max_size-2] = '\r';
buf[max_size-1] = '\n';
const data_packet = buf[0..size];
if (self.device.?.ready() == false) {
return;
}
self.device.?.endpoint_transfer(self.ep_in, data_packet);
}
fn init(ptr: *anyopaque, device: types.UsbDevice) void {
var self: *CdcClassDriver = @ptrCast(@alignCast(ptr));
self.device = device;
self.line_coding = .{
.bit_rate = 115200,
.stop_bits = 0,
.parity = 0,
.data_bits = 8
};
}
fn open(ptr: *anyopaque, cfg: []const u8) !usize {
var self: *CdcClassDriver = @ptrCast(@alignCast(ptr));
var curr_cfg = cfg;
if (bos.try_get_desc_as(types.InterfaceDescriptor, curr_cfg)) |desc_itf| {
if (desc_itf.interface_class != @intFromEnum(types.ClassCode.Cdc)) return types.DriverErrors.UnsupportedInterfaceClassType;
if (desc_itf.interface_subclass != @intFromEnum(CdcCommSubClassType.AbstractControlModel)) return types.DriverErrors.UnsupportedInterfaceSubClassType;
} else {
return types.DriverErrors.ExpectedInterfaceDescriptor;
}
curr_cfg = bos.get_desc_next(curr_cfg);
while (curr_cfg.len > 0 and bos.get_desc_type(curr_cfg) == DescType.CsInterface) {
curr_cfg = bos.get_desc_next(curr_cfg);
}
if (bos.try_get_desc_as(types.EndpointDescriptor, curr_cfg)) |desc_ep| {
self.ep_notif = desc_ep.endpoint_address;
curr_cfg = bos.get_desc_next(curr_cfg);
}
if (bos.try_get_desc_as(types.InterfaceDescriptor, curr_cfg)) |desc_itf| {
if (desc_itf.interface_class == @intFromEnum(types.ClassCode.CdcData)) {
curr_cfg = bos.get_desc_next(curr_cfg);
for (0..2) |_| {
if (bos.try_get_desc_as(types.EndpointDescriptor, curr_cfg)) |desc_ep| {
switch (types.Endpoint.dir_from_address(desc_ep.endpoint_address)) {
.In => { self.ep_in = desc_ep.endpoint_address; },
.Out => { self.ep_out = desc_ep.endpoint_address; },
}
self.device.?.endpoint_open(curr_cfg[0..desc_ep.length]);
curr_cfg = bos.get_desc_next(curr_cfg);
}
}
}
}
return cfg.len - curr_cfg.len;
}
fn class_control(ptr: *anyopaque, stage: types.ControlStage, setup: *const types.SetupPacket) bool {
var self: *CdcClassDriver = @ptrCast(@alignCast(ptr));
if (CdcManagementRequestType.from_u8(setup.request)) |request| {
switch (request) {
.SetLineCoding => {
switch (stage) {
.Setup => {
// HACK, we should handle data phase somehow to read sent line_coding
self.device.?.control_ack(setup);
},
else => {}
}
},
.GetLineCoding => {
if (stage == .Setup) {
self.device.?.control_transfer(setup, std.mem.asBytes(&self.line_coding));
}
},
.SetControlLineState => {
switch (stage) {
.Setup => {
self.device.?.control_ack(setup);
},
else => {}
}
},
.SendBreak => {
switch (stage) {
.Setup => {
self.device.?.control_ack(setup);
},
else => {}
}
}
}
}
return true;
}
pub fn driver(self: *@This()) types.UsbClassDriver {
return .{
.ptr = self,
.fn_init = init,
.fn_open = open,
.fn_class_control = class_control
};
}
};

@ -1,112 +0,0 @@
/// Describes a device. This is the most broad description in USB and is
/// typically the first thing the host asks for.
pub const Device = extern struct {
/// Version of the device descriptor / USB protocol, in binary-coded
/// decimal. This is typically `0x01_10` for USB 1.1.
bcdUSB: u16,
/// Class of device, giving a broad functional area.
bDeviceClass: u8,
/// SubClass of device, refining the class.
bDeviceSubClass: u8,
/// Protocol within the subclass.
bDeviceProtocol: u8,
/// Maximum unit of data this device can move.
bMaxPacketSize0: u8,
/// ID of product vendor.
idVendor: u16,
/// ID of product.
idProduct: u16,
/// Device version number, as BCD again.
bcdDevice: u16,
/// Index of manufacturer name in string descriptor table.
iManufacturer: u8,
/// Index of product name in string descriptor table.
iPRoduct: u8,
/// Index of serial number in string descriptor table.
iSerialNumber: u8,
/// Number of configurations supported by this device.
bNumConfigurations: u8,
};
pub const Interface = extern struct {
bInterfaceNumber: u8,
bAlternateSetting: u8,
bNumEndpoints: u8,
bInterfaceClass: u8,
bInterfaceSubClass: u8,
bInterfaceProtocol: u8,
iInterface: u8,
};
/// Description of a single available device configuration.
pub const Configuration = extern struct {
/// Total length of all descriptors in this configuration, concatenated.
/// This will include this descriptor, plus at least one interface
/// descriptor, plus each interface descriptor's endpoint descriptors.
wTotalLength: u16,
/// Number of interface descriptors in this configuration.
bNumInterfaces: u8,
/// Number to use when requesting this configuration via a
/// `SetConfiguration` request.
bConfigurationValue: u8,
/// Index of this configuration's name in the string descriptor table.
iConfiguration: u8,
/// Bit set of device attributes:
///
/// - Bit 7 should be set (indicates that device can be bus powered in USB
/// 1.0).
/// - Bit 6 indicates that the device can be self-powered.
/// - Bit 5 indicates that the device can signal remote wakeup of the host
/// (like a keyboard).
/// - The rest are reserved and should be zero.
bmAttributes: u8,
/// Maximum device power consumption in units of 2mA.
bMaxPower: u8,
};
pub const InterfaceAssociation = extern struct {
bFirstInterface: u8,
bInterfaceCount: u8,
bFunctionClass: u8,
bFunctionSubClass: u8,
bFunctionProtocol: u8,
iFunction: u8,
};
/// Describes an endpoint within an interface
pub const Endpoint = extern struct {
/// Address of this endpoint, where the bottom 4 bits give the endpoint
/// number (0..15) and the top bit distinguishes IN (1) from OUT (0).
bEndpointAddress: u8,
/// Endpoint attributes; the most relevant part is the bottom 2 bits, which
/// control the transfer type using the values from `TransferType`.
bmAttributes: u8,
/// Maximum packet size this endpoint can accept/produce.
wMaxPacketSize: u16,
/// Interval for polling interrupt/isochronous endpoints (which we don't
/// currently support) in milliseconds.
bInterval: u8,
};
pub const BOS = extern struct {
/// The number of bytes in this descriptor and all of its subordinate
/// descriptors
wTotalLength: u16,
/// The numbre of device capability descriptors subordinate to this BOS
/// descriptor
bNumDeviceCaps: u8,
};
pub const Utf16Le = struct {
bytes: []const u8,
};
/// For string descriptor zero: an array of one or more language identifier
/// codes, for other string descriptors, a unicode UTF-16LE string
pub const String = extern struct {
string_or_lang: union {
bSTRING: Utf16Le,
wLANGID: []const u8,
};
};

@ -43,6 +43,12 @@
const std = @import("std");
const types = @import("types.zig");
const utils = @import("utils.zig");
const DescType = types.DescType;
const bos = utils.BosConfig;
// +++++++++++++++++++++++++++++++++++++++++++++++++
// Common Data Types
// +++++++++++++++++++++++++++++++++++++++++++++++++
@ -68,37 +74,46 @@ const std = @import("std");
// | ReportDescriptor | | PhysicalDesc |
// ----------------------- ---------------------
pub const DescType = enum(u8) {
/// HID descriptor
pub const HidDescType = enum(u8) {
Hid = 0x21,
/// Report descriptor
Report = 0x22,
/// Physical descriptor
Physical = 0x23,
pub fn from_u16(v: u16) ?@This() {
return switch (v) {
0x21 => @This().Hid,
0x22 => @This().Report,
0x23 => @This().Physical,
else => null,
pub fn from_u8(v: u8) ?@This() {
return std.meta.intToEnum(@This(), v) catch null;
}
};
pub const HidRequestType = enum(u8) {
GetReport = 0x01,
GetIdle = 0x02,
GetProtocol = 0x03,
SetReport = 0x09,
SetIdle = 0x0a,
SetProtocol = 0x0b,
pub fn from_u8(v: u8) ?@This() {
return std.meta.intToEnum(@This(), v) catch null;
}
};
/// USB HID descriptor
pub const HidDescriptor = struct {
descriptor_type: DescType = DescType.Hid,
pub const const_descriptor_type = HidDescType.Hid;
length: u8 = 9,
/// Type of this descriptor
descriptor_type: HidDescType = const_descriptor_type,
/// Numeric expression identifying the HID Class Specification release
bcd_hid: u16,
bcd_hid: u16 align(1),
/// Numeric expression identifying country code of the localized hardware
country_code: u8,
/// Numeric expression specifying the number of class descriptors
num_descriptors: u8,
/// Type of HID class report
report_type: DescType = DescType.Report,
report_type: HidDescType = HidDescType.Report,
/// The total size of the Report descriptor
report_length: u16,
report_length: u16 align(1),
pub fn serialize(self: *const @This()) [9]u8 {
var out: [9]u8 = undefined;
@ -249,6 +264,7 @@ pub const LocalItem = enum(u4) {
pub const UsageTable = struct {
const fido: [2]u8 = "\xD0\xF1".*;
const vendor: [2]u8 = "\x00\xFF".*;
};
pub const FidoAllianceUsage = struct {
@ -429,6 +445,126 @@ pub const ReportDescriptorFidoU2f = hid_usage_page(2, UsageTable.fido) //
// End
++ hid_collection_end();
pub const ReportDescriptorGenericInOut = hid_usage_page(2, UsageTable.vendor) //
++ hid_usage(1, "\x01".*) //
++ hid_collection(CollectionItem.Application) //
// Usage Data In
++ hid_usage(1, "\x02".*) //
++ hid_logical_min(1, "\x00".*) //
++ hid_logical_max(2, "\xff\x00".*) //
++ hid_report_size(1, "\x08".*) //
++ hid_report_count(1, "\x40".*) //
++ hid_input(HID_DATA | HID_VARIABLE | HID_ABSOLUTE) //
// Usage Data Out
++ hid_usage(1, "\x03".*) //
++ hid_logical_min(1, "\x00".*) //
++ hid_logical_max(2, "\xff\x00".*) //
++ hid_report_size(1, "\x08".*) //
++ hid_report_count(1, "\x40".*) //
++ hid_output(HID_DATA | HID_VARIABLE | HID_ABSOLUTE) //
// End
++ hid_collection_end();
pub const HidClassDriver = struct {
device: ?types.UsbDevice = null,
ep_in: u8 = 0,
ep_out: u8 = 0,
hid_descriptor: []const u8 = &.{},
report_descriptor: []const u8,
fn init(ptr: *anyopaque, device: types.UsbDevice) void {
var self: *HidClassDriver = @ptrCast(@alignCast(ptr));
self.device = device;
}
fn open(ptr: *anyopaque, cfg: []const u8) !usize {
var self: *HidClassDriver = @ptrCast(@alignCast(ptr));
var curr_cfg = cfg;
if (bos.try_get_desc_as(types.InterfaceDescriptor, curr_cfg)) |desc_itf| {
if (desc_itf.interface_class != @intFromEnum(types.ClassCode.Hid)) return types.DriverErrors.UnsupportedInterfaceClassType;
} else {
return types.DriverErrors.ExpectedInterfaceDescriptor;
}
curr_cfg = bos.get_desc_next(curr_cfg);
if (bos.try_get_desc_as(HidDescriptor, curr_cfg)) |_| {
self.hid_descriptor = curr_cfg[0..bos.get_desc_len(curr_cfg)];
curr_cfg = bos.get_desc_next(curr_cfg);
} else {
return types.DriverErrors.UnexpectedDescriptor;
}
for (0..2) |_| {
if (bos.try_get_desc_as(types.EndpointDescriptor, curr_cfg)) |desc_ep| {
switch (types.Endpoint.dir_from_address(desc_ep.endpoint_address)) {
.In => { self.ep_in = desc_ep.endpoint_address; },
.Out => { self.ep_out = desc_ep.endpoint_address; },
}
self.device.?.endpoint_open(curr_cfg[0..desc_ep.length]);
curr_cfg = bos.get_desc_next(curr_cfg);
}
}
return cfg.len - curr_cfg.len;
}
fn class_control(ptr: *anyopaque, stage: types.ControlStage, setup: *const types.SetupPacket) bool {
var self: *HidClassDriver = @ptrCast(@alignCast(ptr));
switch (setup.request_type.type) {
.Standard => {
if (stage == .Setup) {
const hid_desc_type = HidDescType.from_u8(@intCast((setup.value >> 8) & 0xff));
const request_code = types.SetupRequest.from_u8(setup.request);
if (hid_desc_type == null or request_code == null) {
return false;
}
if (request_code.? == .GetDescriptor and hid_desc_type == .Hid) {
self.device.?.control_transfer(setup, self.hid_descriptor);
} else if (request_code.? == .GetDescriptor and hid_desc_type == .Report) {
self.device.?.control_transfer(setup, self.report_descriptor);
} else {
return false;
}
}
},
.Class => {
const hid_request_type = HidRequestType.from_u8(setup.request);
if (hid_request_type == null) return false;
switch (hid_request_type.?) {
.SetIdle => {
if (stage == .Setup) {
self.device.?.control_ack(setup);
}
},
else => {
return false;
}
}
},
else => {
return false;
}
}
return true;
}
pub fn driver(self: *@This()) types.UsbClassDriver {
return .{
.ptr = self,
.fn_init = init,
.fn_open = open,
.fn_class_control = class_control
};
}
};
test "create hid report item" {
const r = hid_report_item(
2,

@ -0,0 +1,56 @@
const types = @import("types.zig");
const hid = @import("hid.zig");
const cdc = @import("cdc.zig");
pub const DescriptorsConfigTemplates = struct {
pub const config_descriptor_len = 9;
pub fn config_descriptor(config_num: u8, interfaces_num: u8, string_index: u8, total_len: u16, attributes: u8, max_power_ma: u9) [9]u8 {
const desc1 = types.ConfigurationDescriptor { .total_length = total_len, .num_interfaces = interfaces_num, .configuration_value = config_num, .configuration_s = string_index, .attributes = 0b01000000 | attributes, .max_power = max_power_ma/2 };
return desc1.serialize();
}
pub const cdc_descriptor_len = 8 + 9 + 5 + 5 + 4 + 5 + 7 + 9 + 7 + 7;
pub fn cdc_descriptor(interface_number: u8, string_index: u8, endpoint_notifi_address: u8, endpoint_notifi_size: u16, endpoint_out_address: u8, endpoint_in_address: u8, endpoint_size: u16) [cdc_descriptor_len]u8 {
const desc1 = types.InterfaceAssociationDescriptor { .first_interface = interface_number, .interface_count = 2, .function_class = 2, .function_subclass = 2, .function_protocol = 0, .function = 0 };
const desc2 = types.InterfaceDescriptor { .interface_number = interface_number, .alternate_setting = 0, .num_endpoints = 1, .interface_class = 2, .interface_subclass = 2, .interface_protocol = 0, .interface_s = string_index };
const desc3 = cdc.CdcHeaderDescriptor { .descriptor_type = .CsInterface, .descriptor_subtype = .Header, .bcd_cdc = 0x0120 };
const desc4 = cdc.CdcCallManagementDescriptor { .descriptor_type = .CsInterface, .descriptor_subtype = .CallManagement, .capabilities = 0, .data_interface = interface_number + 1 };
const desc5 = cdc.CdcAcmDescriptor { .descriptor_type = .CsInterface, .descriptor_subtype = .ACM, .capabilities = 6 };
const desc6 = cdc.CdcUnionDescriptor { .descriptor_type = .CsInterface, .descriptor_subtype = .Union, .master_interface = interface_number, .slave_interface_0 = interface_number + 1 };
const desc7 = types.EndpointDescriptor { .endpoint_address = endpoint_notifi_address, .attributes = @intFromEnum(types.TransferType.Interrupt), .max_packet_size = endpoint_notifi_size, .interval = 16 };
const desc8 = types.InterfaceDescriptor { .interface_number = interface_number + 1, .alternate_setting = 0, .num_endpoints = 2, .interface_class = 10, .interface_subclass = 0, .interface_protocol = 0, .interface_s = 0 };
const desc9 = types.EndpointDescriptor { .endpoint_address = endpoint_out_address, .attributes = @intFromEnum(types.TransferType.Bulk), .max_packet_size = endpoint_size, .interval = 0 };
const desc10 = types.EndpointDescriptor { .endpoint_address = endpoint_in_address, .attributes = @intFromEnum(types.TransferType.Bulk), .max_packet_size = endpoint_size, .interval = 0 };
return desc1.serialize() ++ desc2.serialize() ++ desc3.serialize() ++ desc4.serialize() ++ desc5.serialize() ++ desc6.serialize() ++ desc7.serialize() ++ desc8.serialize() ++ desc9.serialize() ++ desc10.serialize();
}
pub const hid_in_descriptor_len = 9 + 9 + 7;
pub fn hid_in_descriptor(interface_number: u8, string_index: u8, boot_protocol: u8, report_desc_len: u16, endpoint_in_address: u8, endpoint_size: u16, endpoint_interval: u16) [hid_in_descriptor_len]u8 {
const desc1 = types.InterfaceDescriptor { .interface_number = interface_number, .alternate_setting = 0, .num_endpoints = 1, .interface_class = 3, .interface_subclass = if (boot_protocol > 0) 1 else 0, .interface_protocol = boot_protocol, .interface_s = string_index };
const desc2 = hid.HidDescriptor { .bcd_hid = 0x0111, .country_code = 0, .num_descriptors = 1, .report_length = report_desc_len };
const desc3 = types.EndpointDescriptor { .endpoint_address = endpoint_in_address, .attributes = @intFromEnum(types.TransferType.Interrupt), .max_packet_size = endpoint_size, .interval = endpoint_interval };
return desc1.serialize() ++ desc2.serialize() ++ desc3.serialize();
}
pub const hid_in_out_descriptor_len = 9 + 9 + 7 + 7;
pub fn hid_in_out_descriptor(interface_number: u8, string_index: u8, boot_protocol: u8, report_desc_len: u16, endpoint_out_address: u8, endpoint_in_address: u8, endpoint_size: u16, endpoint_interval: u16) [hid_in_out_descriptor_len]u8 {
const desc1 = types.InterfaceDescriptor { .interface_number = interface_number, .alternate_setting = 0, .num_endpoints = 2, .interface_class = 3, .interface_subclass = if (boot_protocol > 0) 1 else 0, .interface_protocol = boot_protocol, .interface_s = string_index };
const desc2 = hid.HidDescriptor { .bcd_hid = 0x0111, .country_code = 0, .num_descriptors = 1, .report_length = report_desc_len };
const desc3 = types.EndpointDescriptor { .endpoint_address = endpoint_out_address, .attributes = @intFromEnum(types.TransferType.Interrupt), .max_packet_size = endpoint_size, .interval = endpoint_interval };
const desc4 = types.EndpointDescriptor { .endpoint_address = endpoint_in_address, .attributes = @intFromEnum(types.TransferType.Interrupt), .max_packet_size = endpoint_size, .interval = endpoint_interval };
return desc1.serialize() ++ desc2.serialize() ++ desc3.serialize() ++ desc4.serialize();
}
pub const vendor_descriptor_len = 9 + 7 + 7;
pub fn vendor_descriptor(interface_number: u8, string_index: u8, endpoint_out_address: u8, endpoint_in_address: u8, endpoint_size: u16) [vendor_descriptor_len]u8 {
const desc1 = types.InterfaceDescriptor { .interface_number = interface_number, .alternate_setting = 0, .num_endpoints = 2, .interface_class = 0xff, .interface_subclass = 0, .interface_protocol = 0, .interface_s = string_index };
const desc2 = types.EndpointDescriptor { .endpoint_address = endpoint_out_address, .attributes = @intFromEnum(types.TransferType.Bulk), .max_packet_size = endpoint_size, .interval = 0 };
const desc3 = types.EndpointDescriptor { .endpoint_address = endpoint_in_address, .attributes = @intFromEnum(types.TransferType.Bulk), .max_packet_size = endpoint_size, .interval = 0 };
return desc1.serialize() ++ desc2.serialize() ++ desc3.serialize();
}
};

@ -0,0 +1,476 @@
const std = @import("std");
pub const DescType = enum(u8) {
Device = 0x01,
Config = 0x02,
String = 0x03,
Interface = 0x04,
Endpoint = 0x05,
DeviceQualifier = 0x06,
InterfaceAssociation = 0x0b,
CsDevice = 0x21,
CsConfig = 0x22,
CsString = 0x23,
CsInterface = 0x24,
CsEndpoint = 0x25,
pub fn from_u8(v: u8) ?@This() {
return std.meta.intToEnum(@This(), v) catch null;
}
};
pub const ClassCode = enum(u8) {
Unspecified = 0,
Audio = 1,
Cdc = 2,
Hid = 3,
CdcData = 10,
};
/// Types of transfer that can be indicated by the `attributes` field on `EndpointDescriptor`.
pub const TransferType = enum(u2) {
Control = 0,
Isochronous = 1,
Bulk = 2,
Interrupt = 3,
pub fn from_u8(v: u8) ?@This() {
return std.meta.intToEnum(@This(), v) catch null;
}
pub inline fn as_number(self: @This()) u2 {
return @intFromEnum(self);
}
};
pub const ControlStage = enum {
Idle,
Setup,
Data,
Ack
};
/// The types of USB SETUP requests that we understand.
pub const SetupRequest = enum(u8) {
GetDescriptor = 0x06,
SetAddress = 0x05,
SetConfiguration = 0x09,
pub fn from_u8(v: u8) ?@This() {
return std.meta.intToEnum(@This(), v) catch null;
}
};
/// USB deals in two different transfer directions, called OUT (host-to-device)
/// and IN (device-to-host). In the vast majority of cases, OUT is represented
/// by a 0 byte, and IN by an `0x80` byte.
pub const Dir = enum(u1) {
Out = 0,
In = 1,
pub const DIR_IN_MASK = 0x80;
pub inline fn as_number(self: @This()) u1 {
return @intFromEnum(self);
}
pub inline fn as_number_reversed(self: @This()) u1 {
return ~@intFromEnum(self);
}
};
pub const Endpoint = struct {
pub inline fn to_address(num: u8, dir: Dir) u8 {
return switch (dir) {
.Out => num,
.In => num | Dir.DIR_IN_MASK
};
}
pub inline fn num_from_address(addr: u8) u8 {
return addr & ~@as(u8, @intCast(Dir.DIR_IN_MASK));
}
pub inline fn dir_from_address(addr: u8) Dir {
return if (addr & Dir.DIR_IN_MASK != 0) Dir.In else Dir.Out;
}
pub const EP0_OUT_IDX = 0;
pub const EP0_IN_IDX = 1;
pub const EP0_IN_ADDR: u8 = to_address(0, .In);
pub const EP0_OUT_ADDR: u8 = to_address(0, .Out);
};
pub const RequestType = packed struct(u8) {
recipient: Recipient,
type: Type,
direction: Dir,
const Type = enum(u2) {
Standard,
Class,
Vendor,
Other
};
/// RequestType is created from raw bytes using std.mem.bytesToValue, we need to support all potential values if we don't want to crash such conversion
const Recipient = enum(u5) {
Device,
Interface,
Endpoint,
Other,
Reserved1,
Reserved2,
Reserved3,
Reserved4,
Reserved5,
Reserved6,
Reserved7,
Reserved8,
Reserved9,
Reserved10,
Reserved11,
Reserved12,
Reserved13,
Reserved14,
Reserved15,
Reserved16,
Reserved17,
Reserved18,
Reserved19,
Reserved20,
Reserved21,
Reserved22,
Reserved23,
Reserved24,
Reserved25,
Reserved26,
Reserved27,
Reserved28
};
};
/// Layout of an 8-byte USB SETUP packet.
pub const SetupPacket = extern struct {
/// Request metadata: recipient, type, direction.
request_type: RequestType,
/// Request. Standard setup requests are in the `SetupRequest` enum.
/// Devices can extend this with additional types as long as they don't
/// conflict.
request: u8,
/// A simple argument of up to 16 bits, specific to the request.
value: u16,
/// Not used in the requests we support.
index: u16,
/// If data will be transferred after this request (in the direction given
/// by `request_type`), this gives the number of bytes (OUT) or maximum
/// number of bytes (IN).
length: u16,
};
/// Describes an endpoint within an interface
pub const EndpointDescriptor = extern struct {
pub const const_descriptor_type = DescType.Endpoint;
length: u8 = 7,
/// Type of this descriptor, must be `Endpoint`.
descriptor_type: DescType = const_descriptor_type,
/// Address of this endpoint, where the bottom 4 bits give the endpoint
/// number (0..15) and the top bit distinguishes IN (1) from OUT (0).
endpoint_address: u8,
/// Endpoint attributes; the most relevant part is the bottom 2 bits, which
/// control the transfer type using the values from `TransferType`.
attributes: u8,
/// Maximum packet size this endpoint can accept/produce.
max_packet_size: u16 align(1),
/// Interval for polling interrupt/isochronous endpoints (which we don't
/// currently support) in milliseconds.
interval: u8,
pub fn serialize(self: *const @This()) [7]u8 {
var out: [7]u8 = undefined;
out[0] = out.len;
out[1] = @intFromEnum(self.descriptor_type);
out[2] = self.endpoint_address;
out[3] = self.attributes;
out[4] = @intCast(self.max_packet_size & 0xff);
out[5] = @intCast((self.max_packet_size >> 8) & 0xff);
out[6] = self.interval;
return out;
}
};
/// Description of an interface within a configuration.
pub const InterfaceDescriptor = extern struct {
pub const const_descriptor_type = DescType.Interface;
length: u8 = 9,
/// Type of this descriptor, must be `Interface`.
descriptor_type: DescType = const_descriptor_type,
/// ID of this interface.
interface_number: u8,
/// Allows a single `interface_number` to have several alternate interface
/// settings, where each alternate increments this field. Normally there's
/// only one, and `alternate_setting` is zero.
alternate_setting: u8,
/// Number of endpoint descriptors in this interface.
num_endpoints: u8,
/// Interface class code, distinguishing the type of interface.
interface_class: u8,
/// Interface subclass code, refining the class of interface.
interface_subclass: u8,
/// Protocol within the interface class/subclass.
interface_protocol: u8,
/// Index of interface name within string descriptor table.
interface_s: u8,
pub fn serialize(self: *const @This()) [9]u8 {
var out: [9]u8 = undefined;
out[0] = out.len;
out[1] = @intFromEnum(self.descriptor_type);
out[2] = self.interface_number;
out[3] = self.alternate_setting;
out[4] = self.num_endpoints;
out[5] = self.interface_class;
out[6] = self.interface_subclass;
out[7] = self.interface_protocol;
out[8] = self.interface_s;
return out;
}
};
/// USB interface association descriptor (IAD) allows the device to group interfaces that belong to a function.
pub const InterfaceAssociationDescriptor = extern struct {
pub const const_descriptor_type = DescType.InterfaceAssociation;
length: u8 = 8,
// Type of this descriptor, must be `InterfaceAssociation`.
descriptor_type: DescType = const_descriptor_type,
// First interface number of the set of interfaces that follow this
// descriptor.
first_interface: u8,
// The number of interfaces that follow this descriptor that are considered
// associated.
interface_count: u8,
// The interface class used for associated interfaces.
function_class: u8,
// The interface subclass used for associated interfaces.
function_subclass: u8,
// The interface protocol used for associated interfaces.
function_protocol: u8,
// Index of the string descriptor describing the associated interfaces.
function: u8,
pub fn serialize(self: *const @This()) [8]u8 {
var out: [8]u8 = undefined;
out[0] = out.len;
out[1] = @intFromEnum(self.descriptor_type);
out[2] = self.first_interface;
out[3] = self.interface_count;
out[4] = self.function_class;
out[5] = self.function_subclass;
out[6] = self.function_protocol;
out[7] = self.function;
return out;
}
};
/// Description of a single available device configuration.
pub const ConfigurationDescriptor = extern struct {
pub const const_descriptor_type = DescType.Config;
length: u8 = 9,
/// Type of this descriptor, must be `Config`.
descriptor_type: DescType = const_descriptor_type,
/// Total length of all descriptors in this configuration, concatenated.
/// This will include this descriptor, plus at least one interface
/// descriptor, plus each interface descriptor's endpoint descriptors.
total_length: u16 align(1),
/// Number of interface descriptors in this configuration.
num_interfaces: u8,
/// Number to use when requesting this configuration via a
/// `SetConfiguration` request.
configuration_value: u8,
/// Index of this configuration's name in the string descriptor table.
configuration_s: u8,
/// Bit set of device attributes:
///
/// - Bit 7 should be set (indicates that device can be bus powered in USB
/// 1.0).
/// - Bit 6 indicates that the device can be self-powered.
/// - Bit 5 indicates that the device can signal remote wakeup of the host
/// (like a keyboard).
/// - The rest are reserved and should be zero.
attributes: u8,
/// Maximum device power consumption in units of 2mA.
max_power: u8,
pub fn serialize(self: *const @This()) [9]u8 {
var out: [9]u8 = undefined;
out[0] = out.len;
out[1] = @intFromEnum(self.descriptor_type);
out[2] = @intCast(self.total_length & 0xff);
out[3] = @intCast((self.total_length >> 8) & 0xff);
out[4] = self.num_interfaces;
out[5] = self.configuration_value;
out[6] = self.configuration_s;
out[7] = self.attributes;
out[8] = self.max_power;
return out;
}
};
/// Describes a device. This is the most broad description in USB and is
/// typically the first thing the host asks for.
pub const DeviceDescriptor = extern struct {
pub const const_descriptor_type = DescType.Device;
length: u8 = 18,
/// Type of this descriptor, must be `Device`.
descriptor_type: DescType = const_descriptor_type,
/// Version of the device descriptor / USB protocol, in binary-coded
/// decimal. This is typically `0x01_10` for USB 1.1.
bcd_usb: u16 align(1),
/// Class of device, giving a broad functional area.
device_class: u8,
/// Subclass of device, refining the class.
device_subclass: u8,
/// Protocol within the subclass.
device_protocol: u8,
/// Maximum unit of data this device can move.
max_packet_size0: u8,
/// ID of product vendor.
vendor: u16 align(1),
/// ID of product.
product: u16 align(1),
/// Device version number, as BCD again.
bcd_device: u16 align(1),
/// Index of manufacturer name in string descriptor table.
manufacturer_s: u8,
/// Index of product name in string descriptor table.
product_s: u8,
/// Index of serial number in string descriptor table.
serial_s: u8,
/// Number of configurations supported by this device.
num_configurations: u8,
pub fn serialize(self: *const @This()) [18]u8 {
var out: [18]u8 = undefined;
out[0] = out.len;
out[1] = @intFromEnum(self.descriptor_type);
out[2] = @intCast(self.bcd_usb & 0xff);
out[3] = @intCast((self.bcd_usb >> 8) & 0xff);
out[4] = self.device_class;
out[5] = self.device_subclass;
out[6] = self.device_protocol;
out[7] = self.max_packet_size0;
out[8] = @intCast(self.vendor & 0xff);
out[9] = @intCast((self.vendor >> 8) & 0xff);
out[10] = @intCast(self.product & 0xff);
out[11] = @intCast((self.product >> 8) & 0xff);
out[12] = @intCast(self.bcd_device & 0xff);
out[13] = @intCast((self.bcd_device >> 8) & 0xff);
out[14] = self.manufacturer_s;
out[15] = self.product_s;
out[16] = self.serial_s;
out[17] = self.num_configurations;
return out;
}
};
/// USB Device Qualifier Descriptor
/// This descriptor is mostly the same as the DeviceDescriptor
pub const DeviceQualifierDescriptor = extern struct {
pub const const_descriptor_type = DescType.DeviceQualifier;
length: u8 = 10,
/// Type of this descriptor, must be `Device`.
descriptor_type: DescType = const_descriptor_type,
/// Version of the device descriptor / USB protocol, in binary-coded
/// decimal. This is typically `0x01_10` for USB 1.1.
bcd_usb: u16 align(1),
/// Class of device, giving a broad functional area.
device_class: u8,
/// Subclass of device, refining the class.
device_subclass: u8,
/// Protocol within the subclass.
device_protocol: u8,
/// Maximum unit of data this device can move.
max_packet_size0: u8,
/// Number of configurations supported by this device.
num_configurations: u8,
/// Reserved for future use; must be 0
reserved: u8 = 0,
pub fn serialize(self: *const @This()) [10]u8 {
var out: [10]u8 = undefined;
out[0] = out.len;
out[1] = @intFromEnum(self.descriptor_type);
out[2] = @intCast(self.bcd_usb & 0xff);
out[3] = @intCast((self.bcd_usb >> 8) & 0xff);
out[4] = self.device_class;
out[5] = self.device_subclass;
out[6] = self.device_protocol;
out[7] = self.max_packet_size0;
out[8] = self.num_configurations;
out[9] = self.reserved;
return out;
}
};
pub const DriverErrors = error {
ExpectedInterfaceDescriptor,
UnsupportedInterfaceClassType,
UnsupportedInterfaceSubClassType,
UnexpectedDescriptor
};
pub const UsbDevice = struct {
fn_ready: *const fn () bool,
fn_control_transfer: *const fn (setup: *const SetupPacket, data: []const u8) void,
fn_control_ack: *const fn (setup: *const SetupPacket) void,
fn_endpoint_open: *const fn (ep_desc: []const u8) void,
fn_endpoint_transfer: *const fn (ep_addr: u8, data: []const u8) void,
pub fn ready(self: *@This()) bool {
return self.fn_ready();
}
pub fn control_transfer(self: *@This(), setup: *const SetupPacket, data: []const u8) void {
return self.fn_control_transfer(setup, data);
}
pub fn control_ack(self: *@This(), setup: *const SetupPacket) void {
return self.fn_control_ack(setup);
}
pub fn endpoint_open(self: *@This(), ep_desc: []const u8) void {
return self.fn_endpoint_open(ep_desc);
}
pub fn endpoint_transfer(self: *@This(), ep_addr: u8, data: []const u8) void {
return self.fn_endpoint_transfer(ep_addr, data);
}
};
/// USB Class driver interface
pub const UsbClassDriver = struct {
ptr: *anyopaque,
fn_init: *const fn (ptr: *anyopaque, device: UsbDevice) void,
fn_open: *const fn (ptr: *anyopaque, cfg: []const u8) anyerror!usize,
fn_class_control: *const fn (ptr: *anyopaque, stage: ControlStage, setup: *const SetupPacket) bool,
pub fn init(self: *@This(), device: UsbDevice) void {
return self.fn_init(self.ptr, device);
}
/// Driver open (set config) operation. Must return length of consumed driver config data.
pub fn open(self: *@This(), cfg: []const u8) !usize {
return self.fn_open(self.ptr, cfg);
}
pub fn class_control(self: *@This(), stage: ControlStage, setup: *const SetupPacket) bool {
return self.fn_class_control(self.ptr, stage, setup);
}
};

@ -0,0 +1,53 @@
const std = @import("std");
const types = @import("types.zig");
pub const BosConfig = struct {
const DESC_OFFSET_LEN = 0;
const DESC_OFFSET_TYPE = 1;
pub fn get_desc_len(bos_cfg: []const u8) u8 {
return bos_cfg[DESC_OFFSET_LEN];
}
pub fn get_desc_type(bos_cfg: []const u8) ?types.DescType {
return types.DescType.from_u8(bos_cfg[DESC_OFFSET_TYPE]);
}
pub fn get_data_u8(bos_cfg: []const u8, offset: u16) u8 {
return bos_cfg[offset];
}
pub fn get_data_u16(bos_cfg: []const u8, offset: u16) u16 {
const low_byte: u16 = bos_cfg[offset];
const high_byte: u16 = bos_cfg[offset+1];
return (high_byte << 8) | low_byte;
}
/// Only for temporal u8 fields use as u16 fields will have wrong values because BOS endianness
pub fn get_desc_as(comptime T: type, bos_cfg: []const u8) *const T {
return @ptrCast(@constCast(bos_cfg.ptr));
}
/// Only for temporal u8 fields use as u16 fields will have wrong values because BOS endianness
pub fn try_get_desc_as(comptime T: type, bos_cfg: []const u8) ?*const T {
if (bos_cfg.len == 0) return null;
const exp_desc_type = @field(T, "const_descriptor_type");
const cfg_desc_type = bos_cfg[DESC_OFFSET_TYPE];
if (cfg_desc_type != @intFromEnum(exp_desc_type)) {
return null;
}
else {
return @constCast(@ptrCast(bos_cfg.ptr));
}
}
pub fn get_desc_next(bos_cfg: []const u8) []const u8 {
const len = bos_cfg[DESC_OFFSET_LEN];
return bos_cfg[len..];
}
};
test "Test try_get_desc_as" {
const cfg = [_]u8{ 7, 5, 129, 3, 8, 0, 16 };
try std.testing.expect(BosConfig.try_get_desc_as(types.EndpointDescriptor, cfg[0..]) != null);
}

@ -0,0 +1,26 @@
const std = @import("std");
const types = @import("types.zig");
pub const VendorClassDriver = struct {
fn init(_: *anyopaque, _: types.UsbDevice) void {
}
fn open(_: *anyopaque, _: []const u8) !usize {
return 0;
}
pub fn class_control(_: *anyopaque, _: types.ControlStage, _: *const types.SetupPacket) bool {
return true;
}
pub fn driver(self: *@This()) types.UsbClassDriver {
return .{
.ptr = self,
.fn_init = init,
.fn_open = open,
.fn_class_control = class_control
};
}
};

@ -3,12 +3,7 @@ const microzig = @import("microzig");
const app = @import("app");
// Use microzig panic handler if not defined by an application
pub usingnamespace if (!@hasDecl(app, "panic"))
struct {
pub const panic = microzig.panic;
}
else
struct {};
pub const panic = if (!@hasDecl(app, "panic")) microzig.panic else app.panic;
pub const VectorTableOptions = if (@hasDecl(microzig.chip, "VectorTable"))
blk: {

@ -20,7 +20,7 @@ pub fn build(b: *std.Build) void {
.name = example.name,
.target = example.target,
.optimize = optimize,
.root_source_file = .{ .path = example.file },
.root_source_file = b.path(example.file),
});
// `installFirmware()` is the MicroZig pendant to `Build.installArtifact()`

@ -3,10 +3,13 @@ const MicroZig = @import("microzig/build");
const gd32 = @import("microzig/bsp/gigadevice/gd32");
const available_examples = [_]Example{
.{ .target = gd32.chips.gd32vf103xb, .name = "gd32vf103xb", .file = "src/empty.zig" },
.{ .target = gd32.chips.gd32vf103x8, .name = "gd32vf103x8", .file = "src/empty.zig" },
.{ .target = gd32.boards.sipeed.longan_nano, .name = "sipeed-longan_nano", .file = "src/empty.zig" },
.{ .target = gd32.boards.sipeed.longan_nano, .name = "sipeed-longan_nano_blinky", .file = "src/blinky.zig" },
// TODO:
// error: ld.lld: section '.text' will not fit in region 'flash0': overflowed by 152170 bytes
// error: ld.lld: section '.data' will not fit in region 'flash0': overflowed by 161520 bytes
// .{ .target = gd32.chips.gd32vf103xb, .name = "gd32vf103xb", .file = "src/empty.zig" },
// .{ .target = gd32.chips.gd32vf103x8, .name = "gd32vf103x8", .file = "src/empty.zig" },
// .{ .target = gd32.boards.sipeed.longan_nano, .name = "sipeed-longan_nano", .file = "src/empty.zig" },
// .{ .target = gd32.boards.sipeed.longan_nano, .name = "sipeed-longan_nano_blinky", .file = "src/blinky.zig" },
};
pub fn build(b: *std.Build) void {
@ -23,7 +26,7 @@ pub fn build(b: *std.Build) void {
.name = example.name,
.target = example.target,
.optimize = optimize,
.root_source_file = .{ .path = example.file },
.root_source_file = b.path(example.file),
});
// `install_firmware()` is the MicroZig pendant to `Build.installArtifact()`

@ -20,7 +20,7 @@ pub fn build(b: *std.Build) void {
.name = example.name,
.target = example.target,
.optimize = optimize,
.root_source_file = .{ .path = example.file },
.root_source_file = b.path(example.file),
});
// `install_firmware()` is the MicroZig pendant to `Build.installArtifact()`

@ -21,7 +21,7 @@ pub fn build(b: *std.Build) void {
.name = example.name,
.target = example.target,
.optimize = optimize,
.root_source_file = .{ .path = example.file },
.root_source_file = b.path(example.file),
});
// `install_firmware()` is the MicroZig pendant to `Build.installArtifact()`

@ -21,7 +21,7 @@ pub fn build(b: *Build) void {
.name = example.name,
.target = example.target,
.optimize = optimize,
.root_source_file = .{ .path = example.file },
.root_source_file = b.path(example.file),
});
// `install_firmware()` is the MicroZig pendant to `Build.installArtifact()`

@ -20,7 +20,7 @@ pub fn build(b: *std.Build) void {
.name = example.name,
.target = example.target,
.optimize = optimize,
.root_source_file = .{ .path = example.file },
.root_source_file = b.path(example.file),
});
// `install_firmware()` is the MicroZig pendant to `Build.installArtifact()`

@ -15,8 +15,8 @@ const available_examples = [_]Example{
.{ .target = rp2040.boards.raspberrypi.pico, .name = "pico_spi-master", .file = "src/spi_master.zig" },
.{ .target = rp2040.boards.raspberrypi.pico, .name = "pico_squarewave", .file = "src/squarewave.zig" },
.{ .target = rp2040.boards.raspberrypi.pico, .name = "pico_uart", .file = "src/uart.zig" },
.{ .target = rp2040.boards.raspberrypi.pico, .name = "pico_usb-device", .file = "src/usb_device.zig" },
.{ .target = rp2040.boards.raspberrypi.pico, .name = "pico_usb-hid", .file = "src/usb_hid.zig" },
.{ .target = rp2040.boards.raspberrypi.pico, .name = "pico_usb-cdc", .file = "src/usb_cdc.zig" },
.{ .target = rp2040.boards.raspberrypi.pico, .name = "pico_ws2812", .file = "src/ws2812.zig" },
.{ .target = rp2040.boards.raspberrypi.pico, .name = "pico_multicore" , .file = "src/blinky_core1.zig" },
@ -42,7 +42,7 @@ pub fn build(b: *std.Build) void {
.name = example.name,
.target = example.target,
.optimize = optimize,
.root_source_file = .{ .path = example.file },
.root_source_file = b.path(example.file),
});
// `install_firmware()` is the MicroZig pendant to `Build.installArtifact()`

@ -97,7 +97,7 @@ pub fn main() void {
}) catch unreachable;
pio.sm_set_enabled(sm, true);
var rng_src = std.rand.DefaultPrng.init(0x1234);
var rng_src = std.Random.DefaultPrng.init(0x1234);
const rng = rng_src.random();

@ -0,0 +1,105 @@
const std = @import("std");
const microzig = @import("microzig");
const rp2040 = microzig.hal;
const flash = rp2040.flash;
const time = rp2040.time;
const gpio = rp2040.gpio;
const clocks = rp2040.clocks;
const usb = rp2040.usb;
const led = gpio.num(25);
const uart = rp2040.uart.num(0);
const baud_rate = 115200;
const uart_tx_pin = gpio.num(0);
const uart_rx_pin = gpio.num(1);
const usb_config_len = usb.templates.config_descriptor_len + usb.templates.cdc_descriptor_len;
const usb_config_descriptor =
usb.templates.config_descriptor(1, 2, 0, usb_config_len, 0xc0, 100) ++
usb.templates.cdc_descriptor(0, 4, usb.Endpoint.to_address(1, .In), 8, usb.Endpoint.to_address(2, .Out), usb.Endpoint.to_address(2, .In), 64);
var driver_cdc = usb.cdc.CdcClassDriver{};
var drivers = [_]usb.types.UsbClassDriver{ driver_cdc.driver() };
// This is our device configuration
pub var DEVICE_CONFIGURATION: usb.DeviceConfiguration = .{
.device_descriptor = &.{
.descriptor_type = usb.DescType.Device,
.bcd_usb = 0x0200,
.device_class = 0xEF,
.device_subclass = 2,
.device_protocol = 1,
.max_packet_size0 = 64,
.vendor = 0x2E8A,
.product = 0x000a,
.bcd_device = 0x0100,
.manufacturer_s = 1,
.product_s = 2,
.serial_s = 0,
.num_configurations = 1,
},
.config_descriptor = &usb_config_descriptor,
.lang_descriptor = "\x04\x03\x09\x04", // length || string descriptor (0x03) || Engl (0x0409)
.descriptor_strings = &.{
&usb.utils.utf8ToUtf16Le("Raspberry Pi"),
&usb.utils.utf8ToUtf16Le("Pico Test Device"),
&usb.utils.utf8ToUtf16Le("someserial"),
&usb.utils.utf8ToUtf16Le("Board CDC"),
},
.drivers = &drivers
};
pub fn panic(message: []const u8, _: ?*std.builtin.StackTrace, _: ?usize) noreturn {
std.log.err("panic: {s}", .{message});
@breakpoint();
while (true) {}
}
pub const microzig_options = .{
.log_level = .debug,
.logFn = rp2040.uart.log,
};
pub fn main() !void {
led.set_function(.sio);
led.set_direction(.out);
led.put(1);
uart.apply(.{
.baud_rate = baud_rate,
.tx_pin = uart_tx_pin,
.rx_pin = uart_rx_pin,
.clock_config = rp2040.clock_config,
});
rp2040.uart.init_logger(uart);
// First we initialize the USB clock
rp2040.usb.Usb.init_clk();
// Then initialize the USB device using the configuration defined above
rp2040.usb.Usb.init_device(&DEVICE_CONFIGURATION) catch unreachable;
var old: u64 = time.get_time_since_boot().to_us();
var new: u64 = 0;
var i: u32 = 0;
var buf: [1024]u8 = undefined;
while (true) {
// You can now poll for USB events
rp2040.usb.Usb.task(
false, // debug output over UART [Y/n]
) catch unreachable;
new = time.get_time_since_boot().to_us();
if (new - old > 500000) {
old = new;
led.toggle();
i += 1;
// uart log
std.log.info("cdc test: {}\r\n", .{i});
// usb log (at this moment 63 bytes is max limit per single call)
const text = std.fmt.bufPrint(&buf, "cdc test: {}\r\n", .{i}) catch &.{};
driver_cdc.write(text);
}
}
}

@ -1,169 +0,0 @@
const std = @import("std");
const microzig = @import("microzig");
const rp2040 = microzig.hal;
const flash = rp2040.flash;
const time = rp2040.time;
const gpio = rp2040.gpio;
const clocks = rp2040.clocks;
const usb = rp2040.usb;
const led = gpio.num(25);
const uart = rp2040.uart.num(0);
const baud_rate = 115200;
const uart_tx_pin = gpio.num(0);
const uart_rx_pin = gpio.num(1);
// First we define two callbacks that will be used by the endpoints we define next...
fn ep1_in_callback(dc: *usb.DeviceConfiguration, data: []const u8) void {
_ = data;
// The host has collected the data we repeated onto
// EP1! Set up to receive more data on EP1.
usb.Usb.callbacks.usb_start_rx(
dc.endpoints[2], // EP1_OUT_CFG,
64,
);
}
fn ep1_out_callback(dc: *usb.DeviceConfiguration, data: []const u8) void {
// We've gotten data from the host on our custom
// EP1! Set up EP1 to repeat it.
usb.Usb.callbacks.usb_start_tx(
dc.endpoints[3], // EP1_IN_CFG,
data,
);
}
// The endpoints EP0_IN and EP0_OUT are already defined but you can
// add your own endpoints to...
pub var EP1_OUT_CFG: usb.EndpointConfiguration = .{
.descriptor = &usb.EndpointDescriptor{
.descriptor_type = usb.DescType.Endpoint,
.endpoint_address = usb.Dir.Out.endpoint(1),
.attributes = @intFromEnum(usb.TransferType.Bulk),
.max_packet_size = 64,
.interval = 0,
},
.endpoint_control_index = 2,
.buffer_control_index = 3,
.data_buffer_index = 2,
.next_pid_1 = false,
// The callback will be executed if we got an interrupt on EP1_OUT
.callback = ep1_out_callback,
};
pub var EP1_IN_CFG: usb.EndpointConfiguration = .{
.descriptor = &usb.EndpointDescriptor{
.descriptor_type = usb.DescType.Endpoint,
.endpoint_address = usb.Dir.In.endpoint(1),
.attributes = @intFromEnum(usb.TransferType.Bulk),
.max_packet_size = 64,
.interval = 0,
},
.endpoint_control_index = 1,
.buffer_control_index = 2,
.data_buffer_index = 3,
.next_pid_1 = false,
// The callback will be executed if we got an interrupt on EP1_IN
.callback = ep1_in_callback,
};
// This is our device configuration
pub var DEVICE_CONFIGURATION: usb.DeviceConfiguration = .{
.device_descriptor = &.{
.descriptor_type = usb.DescType.Device,
.bcd_usb = 0x0110,
.device_class = 0,
.device_subclass = 0,
.device_protocol = 0,
.max_packet_size0 = 64,
.vendor = 0,
.product = 1,
.bcd_device = 0,
.manufacturer_s = 1,
.product_s = 2,
.serial_s = 0,
.num_configurations = 1,
},
.interface_descriptor = &.{
.descriptor_type = usb.DescType.Interface,
.interface_number = 0,
.alternate_setting = 0,
// We have two endpoints (EP0 IN/OUT don't count)
.num_endpoints = 2,
.interface_class = 0xff,
.interface_subclass = 0,
.interface_protocol = 0,
.interface_s = 0,
},
.config_descriptor = &.{
.descriptor_type = usb.DescType.Config,
// This is calculated via the sizes of underlying descriptors contained in this configuration.
// ConfigurationDescriptor(9) + InterfaceDescriptor(9) * 1 + EndpointDescriptor(8) * 2
.total_length = 34,
.num_interfaces = 1,
.configuration_value = 1,
.configuration_s = 0,
.attributes = 0xc0,
.max_power = 0x32,
},
.lang_descriptor = "\x04\x03\x09\x04", // length || string descriptor (0x03) || Engl (0x0409)
.descriptor_strings = &.{
// ugly unicode :|
"R\x00a\x00s\x00p\x00b\x00e\x00r\x00r\x00y\x00 \x00P\x00i\x00",
"P\x00i\x00c\x00o\x00 \x00T\x00e\x00s\x00t\x00 \x00D\x00e\x00v\x00i\x00c\x00e\x00",
},
// Here we pass all endpoints to the config
// Dont forget to pass EP0_[IN|OUT] in the order seen below!
.endpoints = .{
&usb.EP0_OUT_CFG,
&usb.EP0_IN_CFG,
&EP1_OUT_CFG,
&EP1_IN_CFG,
},
};
pub fn panic(message: []const u8, _: ?*std.builtin.StackTrace, _: ?usize) noreturn {
std.log.err("panic: {s}", .{message});
@breakpoint();
while (true) {}
}
pub const microzig_options = .{
.log_level = .debug,
.logFn = rp2040.uart.log,
};
pub fn main() !void {
led.set_function(.sio);
led.set_direction(.out);
led.put(1);
uart.apply(.{
.baud_rate = baud_rate,
.tx_pin = uart_tx_pin,
.rx_pin = uart_rx_pin,
.clock_config = rp2040.clock_config,
});
rp2040.uart.init_logger(uart);
// First we initialize the USB clock
rp2040.usb.Usb.init_clk();
// Then initialize the USB device using the configuration defined above
rp2040.usb.Usb.init_device(&DEVICE_CONFIGURATION) catch unreachable;
var old: u64 = time.get_time_since_boot().to_us();
var new: u64 = 0;
while (true) {
// You can now poll for USB events
rp2040.usb.Usb.task(
false, // debug output over UART [Y/n]
) catch unreachable;
new = time.get_time_since_boot().to_us();
if (new - old > 500000) {
old = new;
led.toggle();
}
}
}

@ -14,59 +14,14 @@ const baud_rate = 115200;
const uart_tx_pin = gpio.num(0);
const uart_rx_pin = gpio.num(1);
// First we define two callbacks that will be used by the endpoints we define next...
fn ep1_in_callback(dc: *usb.DeviceConfiguration, data: []const u8) void {
_ = data;
// The host has collected the data we repeated onto
// EP1! Set up to receive more data on EP1.
usb.Usb.callbacks.usb_start_rx(
dc.endpoints[2], // EP1_OUT_CFG,
64,
);
}
const usb_packet_size = 64;
const usb_config_len = usb.templates.config_descriptor_len + usb.templates.hid_in_out_descriptor_len;
const usb_config_descriptor =
usb.templates.config_descriptor(1, 1, 0, usb_config_len, 0xc0, 100) ++
usb.templates.hid_in_out_descriptor(0, 0, 0, usb.hid.ReportDescriptorGenericInOut.len, usb.Endpoint.to_address(1, .Out), usb.Endpoint.to_address(1, .In), usb_packet_size, 0);
fn ep1_out_callback(dc: *usb.DeviceConfiguration, data: []const u8) void {
// We've gotten data from the host on our custom
// EP1! Set up EP1 to repeat it.
usb.Usb.callbacks.usb_start_tx(
dc.endpoints[3], // EP1_IN_CFG,
data,
);
}
// The endpoints EP0_IN and EP0_OUT are already defined but you can
// add your own endpoints to...
pub var EP1_OUT_CFG: usb.EndpointConfiguration = .{
.descriptor = &usb.EndpointDescriptor{
.descriptor_type = usb.DescType.Endpoint,
.endpoint_address = usb.Dir.Out.endpoint(1),
.attributes = @intFromEnum(usb.TransferType.Interrupt),
.max_packet_size = 64,
.interval = 0,
},
.endpoint_control_index = 2,
.buffer_control_index = 3,
.data_buffer_index = 2,
.next_pid_1 = false,
// The callback will be executed if we got an interrupt on EP1_OUT
.callback = ep1_out_callback,
};
pub var EP1_IN_CFG: usb.EndpointConfiguration = .{
.descriptor = &usb.EndpointDescriptor{
.descriptor_type = usb.DescType.Endpoint,
.endpoint_address = usb.Dir.In.endpoint(1),
.attributes = @intFromEnum(usb.TransferType.Interrupt),
.max_packet_size = 64,
.interval = 0,
},
.endpoint_control_index = 1,
.buffer_control_index = 2,
.data_buffer_index = 3,
.next_pid_1 = false,
// The callback will be executed if we got an interrupt on EP1_IN
.callback = ep1_in_callback,
};
var driver_hid = usb.hid.HidClassDriver{ .report_descriptor = &usb.hid.ReportDescriptorGenericInOut };
var drivers = [_]usb.types.UsbClassDriver{ driver_hid.driver() };
// This is our device configuration
pub var DEVICE_CONFIGURATION: usb.DeviceConfiguration = .{
@ -78,7 +33,7 @@ pub var DEVICE_CONFIGURATION: usb.DeviceConfiguration = .{
.device_protocol = 0,
.max_packet_size0 = 64,
.vendor = 0xCafe,
.product = 1,
.product = 2,
.bcd_device = 0x0100,
// Those are indices to the descriptor strings
// Make sure to provide enough string descriptors!
@ -87,55 +42,14 @@ pub var DEVICE_CONFIGURATION: usb.DeviceConfiguration = .{
.serial_s = 3,
.num_configurations = 1,
},
.interface_descriptor = &.{
.descriptor_type = usb.DescType.Interface,
.interface_number = 0,
.alternate_setting = 0,
// We have two endpoints (EP0 IN/OUT don't count)
.num_endpoints = 2,
.interface_class = 3,
.interface_subclass = 0,
.interface_protocol = 0,
.interface_s = 0,
},
.config_descriptor = &.{
.descriptor_type = usb.DescType.Config,
// This is calculated via the sizes of underlying descriptors contained in this configuration.
// ConfigurationDescriptor(9) + InterfaceDescriptor(9) * 1 + EndpointDescriptor(8) * 2
.total_length = 34,
.num_interfaces = 1,
.configuration_value = 1,
.configuration_s = 0,
.attributes = 0xc0,
.max_power = 0x32,
},
.config_descriptor = &usb_config_descriptor,
.lang_descriptor = "\x04\x03\x09\x04", // length || string descriptor (0x03) || Engl (0x0409)
.descriptor_strings = &.{
// ugly unicode :|
//"R\x00a\x00s\x00p\x00b\x00e\x00r\x00r\x00y\x00 \x00P\x00i\x00",
&usb.utf8ToUtf16Le("Raspberry Pi"),
//"P\x00i\x00c\x00o\x00 \x00T\x00e\x00s\x00t\x00 \x00D\x00e\x00v\x00i\x00c\x00e\x00",
&usb.utf8ToUtf16Le("Pico Test Device"),
//"c\x00a\x00f\x00e\x00b\x00a\x00b\x00e\x00",
&usb.utf8ToUtf16Le("cafebabe"),
},
.hid = .{
.hid_descriptor = &.{
.bcd_hid = 0x0111,
.country_code = 0,
.num_descriptors = 1,
.report_length = 34,
},
.report_descriptor = &usb.hid.ReportDescriptorFidoU2f,
},
// Here we pass all endpoints to the config
// Dont forget to pass EP0_[IN|OUT] in the order seen below!
.endpoints = .{
&usb.EP0_OUT_CFG,
&usb.EP0_IN_CFG,
&EP1_OUT_CFG,
&EP1_IN_CFG,
&usb.utils.utf8ToUtf16Le("Raspberry Pi"),
&usb.utils.utf8ToUtf16Le("Pico Test Device"),
&usb.utils.utf8ToUtf16Le("cafebabe"),
},
.drivers = &drivers
};
pub fn panic(message: []const u8, _: ?*std.builtin.StackTrace, _: ?usize) noreturn {
@ -172,7 +86,7 @@ pub fn main() !void {
while (true) {
// You can now poll for USB events
rp2040.usb.Usb.task(
true, // debug output over UART [Y/n]
false, // debug output over UART [Y/n]
) catch unreachable;
new = time.get_time_since_boot().to_us();

@ -3,7 +3,10 @@ const MicroZig = @import("microzig/build");
const stm32 = @import("microzig/bsp/stmicro/stm32");
const available_examples = [_]Example{
.{ .target = stm32.chips.stm32f103x8, .name = "stm32f103x8", .file = "src/blinky.zig" },
// error: ld.lld: section '.text' will not fit in region 'flash0': overflowed by 73532 bytes
// error: ld.lld: section '.ARM.exidx' will not fit in region 'flash0': overflowed by 74148 bytes
// error: ld.lld: section '.data' will not fit in region 'flash0': overflowed by 86028 bytes
// TODO: .{ .target = stm32.chips.stm32f103x8, .name = "stm32f103x8", .file = "src/blinky.zig" },
// TODO: .{ .target = stm32.chips.stm32f303vc, .name = "stm32f303vc", .file = "src/blinky.zig" },
// TODO: .{ .target = stm32.chips.stm32f407vg, .name = "stm32f407vg", .file = "src/blinky.zig" },
// TODO: .{ .target = stm32.chips.stm32f429zit6u, .name = "stm32f429zit6u", .file = "src/blinky.zig" },
@ -27,7 +30,7 @@ pub fn build(b: *std.Build) void {
.name = example.name,
.target = example.target,
.optimize = optimize,
.root_source_file = .{ .path = example.file },
.root_source_file = b.path(example.file),
});
// `install_firmware()` is the MicroZig pendant to `Build.installArtifact()`

@ -0,0 +1,19 @@
Copyright (c) Zig Embedded Group contributors
This software is provided 'as-is', without any express or implied warranty. In
no event will the authors be held liable for any damages arising from the use
of this software.
Permission is granted to anyone to use this software for any purpose, including
commercial applications, and to alter it and redistribute it freely, subject to
the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim
that you wrote the original software. If you use this software in a product,
an acknowledgment in the product documentation would be appreciated but is
not required.
2. Altered source versions must be plainly marked as such, and must not be
misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.

@ -0,0 +1,30 @@
const std = @import("std");
const MicroZig = @import("microzig/build");
const ch32 = @import("microzig/bsp/wch/ch32");
const available_examples = [_]Example{
.{ .target = ch32.chips.ch32v003xx, .name = "ch32v003xx_empty", .file = "src/empty.zig" },
.{ .target = ch32.chips.ch32v003xx, .name = "ch32v003xx_blinky", .file = "src/blinky.zig" },
};
pub fn build(b: *std.Build) void {
const microzig = MicroZig.init(b, .{});
const optimize = b.standardOptimizeOption(.{});
for (available_examples) |example| {
const firmware = microzig.add_firmware(b, .{
.name = example.name,
.target = example.target,
.optimize = optimize,
.root_source_file = b.path(example.file),
});
microzig.install_firmware(b, firmware, .{});
microzig.install_firmware(b, firmware, .{ .format = .bin });
}
}
const Example = struct {
target: MicroZig.Target,
name: []const u8,
file: []const u8,
};

@ -0,0 +1,15 @@
.{
.name = "examples/wch/ch32",
.version = "0.0.0",
.dependencies = .{
.@"microzig/build" = .{ .path = "../../../build" },
.@"microzig/bsp/wch/ch32" = .{ .path = "../../../bsp/wch/ch32" },
},
.paths = .{
"LICENSE",
"build.zig",
"build.zig.zon",
"src",
},
}

@ -0,0 +1,15 @@
const std = @import("std");
const mz = @import("microzig");
const periph = mz.chip.peripherals;
pub fn main() !void {
mz.hal.rcc_init_hsi_pll();
periph.RCC.APB2PCENR.modify(.{ .IOPCEN = 1 });
periph.GPIOC.CFGLR.modify(.{ .CNF1 = 0b00, .MODE1 = 0b11 });
var on: u1 = 0;
while (true) {
on ^= 1;
periph.GPIOC.OUTDR.modify(.{ .ODR1 = on });
}
}

@ -0,0 +1,6 @@
const std = @import("std");
const microzig = @import("microzig");
pub fn main() !void {
asm volatile ("nop");
}

@ -19,11 +19,27 @@
"flake-compat_2": {
"flake": false,
"locked": {
"lastModified": 1673956053,
"narHash": "sha256-4gtG9iQuiKITOjNQQeQIpoIB6b16fm+504Ch3sNKLd8=",
"lastModified": 1696426674,
"narHash": "sha256-kvjfFW7WAETZlt09AgDn1MrtKzP7t90Vf7vypd3OL1U=",
"owner": "edolstra",
"repo": "flake-compat",
"rev": "0f9255e01c2351cc7d116c072cb317785dd33b33",
"type": "github"
},
"original": {
"owner": "edolstra",
"repo": "flake-compat",
"type": "github"
}
},
"flake-compat_3": {
"flake": false,
"locked": {
"lastModified": 1696426674,
"narHash": "sha256-kvjfFW7WAETZlt09AgDn1MrtKzP7t90Vf7vypd3OL1U=",
"owner": "edolstra",
"repo": "flake-compat",
"rev": "35bb57c0c8d8b62bbfd284272c928ceb64ddbde9",
"rev": "0f9255e01c2351cc7d116c072cb317785dd33b33",
"type": "github"
},
"original": {
@ -37,11 +53,11 @@
"systems": "systems"
},
"locked": {
"lastModified": 1701680307,
"narHash": "sha256-kAuep2h5ajznlPMD9rnQyffWG8EM/C73lejGofXvdM8=",
"lastModified": 1710146030,
"narHash": "sha256-SZ5L6eA7HJ/nmkzGG7/ISclqe6oZdOZTNoesiInkXPQ=",
"owner": "numtide",
"repo": "flake-utils",
"rev": "4022d587cbbfd70fe950c1e2083a02621806a725",
"rev": "b1d9ab70662946ef0850d488da1c9019f3a9752a",
"type": "github"
},
"original": {
@ -51,12 +67,51 @@
}
},
"flake-utils_2": {
"inputs": {
"systems": "systems_2"
},
"locked": {
"lastModified": 1705309234,
"narHash": "sha256-uNRRNRKmJyCRC/8y1RqBkqWBLM034y4qN7EprSdmgyA=",
"owner": "numtide",
"repo": "flake-utils",
"rev": "1ef2e671c3b0c19053962c07dbda38332dcebf26",
"type": "github"
},
"original": {
"owner": "numtide",
"repo": "flake-utils",
"type": "github"
}
},
"flake-utils_3": {
"inputs": {
"systems": "systems_3"
},
"locked": {
"lastModified": 1710146030,
"narHash": "sha256-SZ5L6eA7HJ/nmkzGG7/ISclqe6oZdOZTNoesiInkXPQ=",
"owner": "numtide",
"repo": "flake-utils",
"rev": "b1d9ab70662946ef0850d488da1c9019f3a9752a",
"type": "github"
},
"original": {
"owner": "numtide",
"repo": "flake-utils",
"type": "github"
}
},
"flake-utils_4": {
"inputs": {
"systems": "systems_4"
},
"locked": {
"lastModified": 1659877975,
"narHash": "sha256-zllb8aq3YO3h8B/U0/J1WBgAL8EX5yWf5pMj3G0NAmc=",
"lastModified": 1705309234,
"narHash": "sha256-uNRRNRKmJyCRC/8y1RqBkqWBLM034y4qN7EprSdmgyA=",
"owner": "numtide",
"repo": "flake-utils",
"rev": "c0e246b9b83f637f4681389ecabcb2681b4f3af0",
"rev": "1ef2e671c3b0c19053962c07dbda38332dcebf26",
"type": "github"
},
"original": {
@ -65,13 +120,46 @@
"type": "github"
}
},
"gitignore": {
"inputs": {
"nixpkgs": [
"zls",
"nixpkgs"
]
},
"locked": {
"lastModified": 1709087332,
"narHash": "sha256-HG2cCnktfHsKV0s4XW83gU3F57gaTljL9KNSuG6bnQs=",
"owner": "hercules-ci",
"repo": "gitignore.nix",
"rev": "637db329424fd7e46cf4185293b9cc8c88c95394",
"type": "github"
},
"original": {
"owner": "hercules-ci",
"repo": "gitignore.nix",
"type": "github"
}
},
"langref": {
"flake": false,
"locked": {
"narHash": "sha256-O6p2tiKD8ZMhSX+DeA/o5hhAvcPkU2J9lFys/r11peY=",
"type": "file",
"url": "https://raw.githubusercontent.com/ziglang/zig/0fb2015fd3422fc1df364995f9782dfe7255eccd/doc/langref.html.in"
},
"original": {
"type": "file",
"url": "https://raw.githubusercontent.com/ziglang/zig/0fb2015fd3422fc1df364995f9782dfe7255eccd/doc/langref.html.in"
}
},
"nixpkgs": {
"locked": {
"lastModified": 1704766047,
"narHash": "sha256-q9tH9yvUWVBh5XpWafpCYAYf72ZyNhfmpgfR4fwM6uw=",
"lastModified": 1719957072,
"narHash": "sha256-gvFhEf5nszouwLAkT9nWsDzocUTqLWHuL++dvNjMp9I=",
"owner": "nixos",
"repo": "nixpkgs",
"rev": "cc2f101c016d42b728a9cb8244215a5d2d98f6df",
"rev": "7144d6241f02d171d25fba3edeaf15e0f2592105",
"type": "github"
},
"original": {
@ -83,16 +171,32 @@
},
"nixpkgs_2": {
"locked": {
"lastModified": 1702350026,
"narHash": "sha256-A+GNZFZdfl4JdDphYKBJ5Ef1HOiFsP18vQe9mqjmUis=",
"lastModified": 1708161998,
"narHash": "sha256-6KnemmUorCvlcAvGziFosAVkrlWZGIc6UNT9GUYr0jQ=",
"owner": "NixOS",
"repo": "nixpkgs",
"rev": "84d981bae8b5e783b3b548de505b22880559515f",
"type": "github"
},
"original": {
"owner": "NixOS",
"ref": "nixos-23.11",
"repo": "nixpkgs",
"type": "github"
}
},
"nixpkgs_3": {
"locked": {
"lastModified": 1718208800,
"narHash": "sha256-US1tAChvPxT52RV8GksWZS415tTS7PV42KTc2PNDBmc=",
"owner": "NixOS",
"repo": "nixpkgs",
"rev": "9463103069725474698139ab10f17a9d125da859",
"rev": "cc54fb41d13736e92229c21627ea4f22199fee6b",
"type": "github"
},
"original": {
"owner": "NixOS",
"ref": "nixos-23.05",
"ref": "nixos-24.05",
"repo": "nixpkgs",
"type": "github"
}
@ -102,7 +206,8 @@
"flake-compat": "flake-compat",
"flake-utils": "flake-utils",
"nixpkgs": "nixpkgs",
"zig": "zig"
"zig": "zig",
"zls": "zls"
}
},
"systems": {
@ -120,6 +225,51 @@
"type": "github"
}
},
"systems_2": {
"locked": {
"lastModified": 1681028828,
"narHash": "sha256-Vy1rq5AaRuLzOxct8nz4T6wlgyUR7zLU309k9mBC768=",
"owner": "nix-systems",
"repo": "default",
"rev": "da67096a3b9bf56a91d16901293e51ba5b49a27e",
"type": "github"
},
"original": {
"owner": "nix-systems",
"repo": "default",
"type": "github"
}
},
"systems_3": {
"locked": {
"lastModified": 1681028828,
"narHash": "sha256-Vy1rq5AaRuLzOxct8nz4T6wlgyUR7zLU309k9mBC768=",
"owner": "nix-systems",
"repo": "default",
"rev": "da67096a3b9bf56a91d16901293e51ba5b49a27e",
"type": "github"
},
"original": {
"owner": "nix-systems",
"repo": "default",
"type": "github"
}
},
"systems_4": {
"locked": {
"lastModified": 1681028828,
"narHash": "sha256-Vy1rq5AaRuLzOxct8nz4T6wlgyUR7zLU309k9mBC768=",
"owner": "nix-systems",
"repo": "default",
"rev": "da67096a3b9bf56a91d16901293e51ba5b49a27e",
"type": "github"
},
"original": {
"owner": "nix-systems",
"repo": "default",
"type": "github"
}
},
"zig": {
"inputs": {
"flake-compat": "flake-compat_2",
@ -127,11 +277,34 @@
"nixpkgs": "nixpkgs_2"
},
"locked": {
"lastModified": 1704283725,
"narHash": "sha256-sRWv8au/59BZpWpqqC8PaGDC9bUNhRIMzanF1zPnXNQ=",
"lastModified": 1720527051,
"narHash": "sha256-87aaUnHa8PzRlnQUR2mLn7BouthbhimExlPdlgu5C0E=",
"owner": "mitchellh",
"repo": "zig-overlay",
"rev": "7789c58ba03f3eb018e7cf60bbcdff2e1e9eb643",
"type": "github"
},
"original": {
"owner": "mitchellh",
"repo": "zig-overlay",
"type": "github"
}
},
"zig-overlay": {
"inputs": {
"flake-compat": "flake-compat_3",
"flake-utils": "flake-utils_4",
"nixpkgs": [
"zls",
"nixpkgs"
]
},
"locked": {
"lastModified": 1718539737,
"narHash": "sha256-hvQ900gSqzGnJWMRQwv65TixciIbC44iX0Nh5ENRwCU=",
"owner": "mitchellh",
"repo": "zig-overlay",
"rev": "f06e268e24a71922ff8b20c94cff1d2afcbd4ab5",
"rev": "6eb42ce6f85d247b1aecf854c45d80902821d0ad",
"type": "github"
},
"original": {
@ -139,6 +312,28 @@
"repo": "zig-overlay",
"type": "github"
}
},
"zls": {
"inputs": {
"flake-utils": "flake-utils_3",
"gitignore": "gitignore",
"langref": "langref",
"nixpkgs": "nixpkgs_3",
"zig-overlay": "zig-overlay"
},
"locked": {
"lastModified": 1720349156,
"narHash": "sha256-eTjMZ/PEkzR+68C1hUwz9Qh/gizxwNG5PkMaDgplEZk=",
"owner": "zigtools",
"repo": "zls",
"rev": "fbd8b9a87a3cd5ab8389054815d9e3f81dfd430b",
"type": "github"
},
"original": {
"owner": "zigtools",
"repo": "zls",
"type": "github"
}
}
},
"root": "root",

@ -8,6 +8,9 @@
# required for latest zig
zig.url = "github:mitchellh/zig-overlay";
zls.url = "github:zigtools/zls";
# Used for shell.nix
flake-compat = {
url = github:edolstra/flake-compat;
@ -26,6 +29,7 @@
# Other overlays
(final: prev: {
zigpkgs = inputs.zig.packages.${prev.system};
zls = inputs.zls.packages.${prev.system}.zls;
})
];
@ -84,7 +88,8 @@
rec {
devShells.default = pkgs.mkShell {
nativeBuildInputs = [
pkgs.zigpkgs."0.11.0"
pkgs.zigpkgs."0.13.0"
pkgs.zls
(python3.withPackages (ps: [
ps.dataclasses_json
ps.marshmallow

@ -16,7 +16,7 @@ pub fn build(b: *Build) !void {
const regz = b.addExecutable(.{
.name = "regz",
.root_source_file = .{ .path = "src/main.zig" },
.root_source_file = b.path("src/main.zig"),
.target = target,
.optimize = optimize,
});
@ -24,7 +24,7 @@ pub fn build(b: *Build) !void {
b.installArtifact(regz);
const exported_module = b.addModule("regz", .{
.root_source_file = .{ .path = "src/module.zig" },
.root_source_file = b.path("src/module.zig"),
});
exported_module.linkLibrary(libxml2_dep.artifact("xml2"));
@ -39,9 +39,7 @@ pub fn build(b: *Build) !void {
const contextualize_fields = b.addExecutable(.{
.name = "contextualize-fields",
.root_source_file = .{
.path = "src/contextualize-fields.zig",
},
.root_source_file = b.path("src/contextualize-fields.zig"),
.target = b.host,
});
contextualize_fields.linkLibrary(libxml2_dep.artifact("xml2"));
@ -54,9 +52,7 @@ pub fn build(b: *Build) !void {
const characterize = b.addExecutable(.{
.name = "characterize",
.root_source_file = .{
.path = "src/characterize.zig",
},
.root_source_file = b.path("src/characterize.zig"),
.target = b.host,
});
characterize.linkLibrary(libxml2_dep.artifact("xml2"));
@ -65,9 +61,7 @@ pub fn build(b: *Build) !void {
characterize_step.dependOn(&characterize_run.step);
const tests = b.addTest(.{
.root_source_file = .{
.path = "src/Database.zig",
},
.root_source_file = b.path("src/Database.zig"),
.target = target,
.optimize = optimize,
});

@ -12,8 +12,8 @@
},
.dependencies = .{
.libxml2 = .{
.url = "https://github.com/mattnite/zig-build-libxml2/archive/fca6bbd7f73914acaea685c544d91608797546a8.tar.gz",
.hash = "1220c3e12fc08c12d6fc52bcc0ae8b180a69abc08212350e2708d4851879f4c814da",
.url = "https://github.com/mattnite/zig-build-libxml2/archive/fab68b5fb06704ef4bdaa221726493a4b6af04b5.tar.gz",
.hash = "122084531ab8ba877a0178fb177a61f6dc9bed56bdcdfb11ad362f352680c04d84cb",
},
},
}

@ -120,6 +120,9 @@ pub const Arch = enum {
// mips
mips,
// riscv
qingke_v2,
pub fn to_string(arch: Arch) []const u8 {
return inline for (@typeInfo(Arch).Enum.fields) |field| {
if (@field(Arch, field.name) == arch)
@ -176,6 +179,13 @@ pub const Arch = enum {
else => false,
};
}
pub fn is_riscv(arch: Arch) bool {
return switch (arch) {
.qingke_v2 => true,
else => false,
};
}
};
// not sure how to communicate the *_once values in generated code
@ -763,7 +773,7 @@ pub fn add_child(
});
assert(db.entity_is(entity_location, child_id));
comptime var it = std.mem.tokenize(u8, entity_location, ".");
comptime var it = std.mem.tokenizeScalar(u8, entity_location, '.');
// the tables are in plural form but "type.peripheral" feels better to me
// for calling this function
_ = comptime it.next();
@ -796,7 +806,7 @@ pub fn add_device_property(
// TODO: assert that entity is only found in one table
pub fn entity_is(db: Database, comptime entity_location: []const u8, id: EntityId) bool {
comptime var it = std.mem.tokenize(u8, entity_location, ".");
comptime var it = std.mem.tokenizeScalar(u8, entity_location, '.');
// the tables are in plural form but "type.peripheral" feels better to me
// for calling this function
const group = comptime (it.next() orelse unreachable) ++ "s";
@ -811,7 +821,7 @@ pub fn get_entity_id_by_name(
comptime entity_location: []const u8,
name: []const u8,
) !EntityId {
comptime var tok_it = std.mem.tokenize(u8, entity_location, ".");
comptime var tok_it = std.mem.tokenizeScalar(u8, entity_location, '.');
// the tables are in plural form but "type.peripheral" feels better to me
// for calling this function
const group = comptime (tok_it.next() orelse unreachable) ++ "s";

@ -0,0 +1,95 @@
//! codegen specific to riscv
const std = @import("std");
const assert = std.debug.assert;
const Database = @import("../Database.zig");
const Arch = Database.Arch;
const EntityId = Database.EntityId;
const gen = @import("../gen.zig");
const InterruptWithIndexAndName = @import("InterruptWithIndexAndName.zig");
const log = std.log.scoped(.@"gen.riscv");
pub fn write_interrupt_vector(
db: Database,
device_id: EntityId,
writer: anytype,
) !void {
assert(db.entity_is("instance.device", device_id));
const arch = db.instances.devices.get(device_id).?.arch;
assert(arch.is_riscv());
try writer.writeAll(
\\pub const VectorTable = extern struct {
\\ const Handler = micro.interrupt.Handler;
\\ const unhandled = micro.interrupt.unhandled;
\\
);
var index: i32 = 0;
if (arch == .qingke_v2) { // CPU specific vectors
try writer.writeAll(
\\ reserved1: [1]u32 = undefined,
\\ NMI: Handler = unhandled,
\\ EXC: Handler = unhandled,
\\ reserved4: [8]u32 = undefined,
\\ SysTick: Handler = unhandled,
\\ reserved13: [1]u32 = undefined,
\\ SWI: Handler = unhandled,
\\ reserved15: [1]u32 = undefined,
\\
);
index = 16;
}
if (db.children.interrupts.get(device_id)) |interrupt_set| {
var interrupts = std.ArrayList(InterruptWithIndexAndName).init(db.gpa);
defer interrupts.deinit();
var it = interrupt_set.iterator();
while (it.next()) |entry| {
const interrupt_id = entry.key_ptr.*;
const interrupt_index = db.instances.interrupts.get(interrupt_id).?;
const name = db.attrs.name.get(interrupt_id) orelse continue;
try interrupts.append(.{
.id = interrupt_id,
.name = name,
.index = interrupt_index,
});
}
std.sort.insertion(
InterruptWithIndexAndName,
interrupts.items,
{},
InterruptWithIndexAndName.less_than,
);
for (interrupts.items) |interrupt| {
if (index < interrupt.index) {
try writer.print("reserved{}: [{}]u32 = undefined,\n", .{
index,
interrupt.index - index,
});
index = interrupt.index;
} else if (index > interrupt.index) {
log.warn("skipping interrupt: {s}", .{interrupt.name});
continue;
}
if (db.attrs.description.get(interrupt.id)) |description|
try gen.write_comment(db.gpa, description, writer);
try writer.print("{}: Handler = unhandled,\n", .{
std.zig.fmtId(interrupt.name),
});
index += 1;
}
}
try writer.writeAll("};\n\n");
}

@ -519,7 +519,7 @@ fn assign_modes_to_entity(
return;
};
var tok_it = std.mem.tokenize(u8, mode_names, " ");
var tok_it = std.mem.tokenizeScalar(u8, mode_names, ' ');
while (tok_it.next()) |mode_str| {
for (mode_set.keys()) |mode_id| {
if (db.attrs.name.get(mode_id)) |name|

@ -9,6 +9,7 @@ const EntitySet = Database.EntitySet;
const arm = @import("arch/arm.zig");
const avr = @import("arch/avr.zig");
const riscv = @import("arch/riscv.zig");
const log = std.log.scoped(.gen);
@ -77,7 +78,7 @@ pub fn write_comment(allocator: Allocator, comment: []const u8, writer: anytype)
defer tokenized.deinit();
var first = true;
var tok_it = std.mem.tokenize(u8, comment, "\n\r \t");
var tok_it = std.mem.tokenizeAny(u8, comment, "\n\r \t");
while (tok_it.next()) |token| {
if (!first)
first = false
@ -90,7 +91,7 @@ pub fn write_comment(allocator: Allocator, comment: []const u8, writer: anytype)
const unescaped = try std.mem.replaceOwned(u8, allocator, tokenized.items, "\\n", "\n");
defer allocator.free(unescaped);
var line_it = std.mem.tokenize(u8, unescaped, "\n");
var line_it = std.mem.tokenizeScalar(u8, unescaped, '\n');
while (line_it.next()) |line|
try writer.print("/// {s}\n", .{line});
}
@ -98,7 +99,7 @@ pub fn write_comment(allocator: Allocator, comment: []const u8, writer: anytype)
fn write_string(str: []const u8, writer: anytype) !void {
if (std.mem.containsAtLeast(u8, str, 1, "\n")) {
try writer.writeByte('\n');
var line_it = std.mem.split(u8, str, "\n");
var line_it = std.mem.splitScalar(u8, str, '\n');
while (line_it.next()) |line|
try writer.print("\\\\{s}\n", .{line});
} else {
@ -232,6 +233,8 @@ fn write_vector_table(
try arm.write_interrupt_vector(db, device_id, writer)
else if (arch.is_avr())
try avr.write_interrupt_vector(db, device_id, writer)
else if (arch.is_riscv())
try riscv.write_interrupt_vector(db, device_id, writer)
else if (arch == .unknown)
return
else
@ -511,7 +514,7 @@ fn write_mode_enum_and_fn(
defer components.deinit();
const mode = db.types.modes.get(mode_id).?;
var tok_it = std.mem.tokenize(u8, mode.qualifier, ".");
var tok_it = std.mem.tokenizeScalar(u8, mode.qualifier, '.');
while (tok_it.next()) |token|
try components.append(token);
@ -526,7 +529,7 @@ fn write_mode_enum_and_fn(
});
try writer.writeAll("switch (value) {\n");
tok_it = std.mem.tokenize(u8, mode.value, " ");
tok_it = std.mem.tokenizeScalar(u8, mode.value, ' ');
while (tok_it.next()) |token| {
const value = try std.fmt.parseInt(u64, token, 0);
try writer.print("{},\n", .{value});

@ -75,7 +75,7 @@ fn entity_type_to_string(entity_type: Database.EntityType) []const u8 {
};
}
const string_to_entity_type_map = std.ComptimeStringMap(Database.EntityType, .{
const string_to_entity_type_map = std.StaticStringMap(Database.EntityType).initComptime(.{
.{ "peripherals", .peripheral },
.{ "register_groups", .register_group },
.{ "registers", .register },
@ -166,7 +166,7 @@ fn resolve_enums(ctx: *LoadContext) !void {
fn ref_to_id(db: Database, ref: []const u8) !EntityId {
// TODO: do proper tokenization since we'll need to handle @"" fields. okay to leave for now.
var it = std.mem.tokenize(u8, ref, ".");
var it = std.mem.tokenizeScalar(u8, ref, '.');
const first = it.next() orelse return error.Malformed;
return if (std.mem.eql(u8, "types", first)) blk: {
var tmp_id: ?EntityId = null;

@ -44,7 +44,7 @@ const Context = struct {
}
};
const svd_boolean = std.ComptimeStringMap(bool, .{
const svd_boolean = std.StaticStringMap(bool).initComptime(.{
.{ "true", true },
.{ "1", true },
.{ "false", false },
@ -215,6 +215,8 @@ fn arch_from_str(str: []const u8) Database.Arch {
.cortex_a57
else if (std.mem.eql(u8, "CA72", str))
.cortex_a72
else if (std.mem.eql(u8, "QINGKEV2", str))
.qingke_v2
else
.unknown;
}
@ -680,7 +682,7 @@ const BitRange = struct {
const bit_range_opt = node.get_value("bitRange");
if (bit_range_opt) |bit_range_str| {
var it = std.mem.tokenize(u8, bit_range_str, "[:]");
var it = std.mem.tokenizeAny(u8, bit_range_str, "[:]");
const msb = try std.fmt.parseInt(u8, it.next() orelse return error.NoMsb, 0);
const lsb = try std.fmt.parseInt(u8, it.next() orelse return error.NoLsb, 0);

@ -36,18 +36,18 @@ pub fn build(b: *std.Build) void {
const elf2uf2 = b.addExecutable(.{
.name = "elf2uf2",
.root_source_file = .{ .path = "src/elf2uf2.zig" },
.root_source_file = b.path("src/elf2uf2.zig"),
.target = target,
.optimize = optimize,
});
b.installArtifact(elf2uf2);
_ = b.addModule("uf2", .{
.root_source_file = .{ .path = "src/uf2.zig" },
.root_source_file = b.path("src/uf2.zig"),
});
const main_tests = b.addTest(.{
.root_source_file = .{ .path = "src/uf2.zig" },
.root_source_file = b.path("src/uf2.zig"),
});
const run_main_tests = b.addRunArtifact(main_tests);
@ -56,7 +56,7 @@ pub fn build(b: *std.Build) void {
const gen = b.addExecutable(.{
.name = "gen",
.root_source_file = .{ .path = "src/gen.zig" },
.root_source_file = b.path("src/gen.zig"),
.target = b.host,
});
const gen_run_step = b.addRunArtifact(gen);
@ -65,7 +65,7 @@ pub fn build(b: *std.Build) void {
const example = b.addExecutable(.{
.name = "example",
.root_source_file = .{ .path = "src/example.zig" },
.root_source_file = b.path("src/example.zig"),
.target = b.host,
});
b.installArtifact(example);

Loading…
Cancel
Save