Refactors packaging process from bash to python

wch-ch32v003
Felix "xq" Queißner 9 months ago
parent bb2b13227b
commit 31f26f57d9

@ -0,0 +1,2 @@
# use_nix
use_flake

1
.gitignore vendored

@ -4,3 +4,4 @@ microzig-deploy/
.DS_Store .DS_Store
.gdbinit .gdbinit
.lldbinit .lldbinit
.direnv/

@ -1,5 +0,0 @@
.{
.name = "microzig-espressif-esp",
.version = "0.1.0",
.dependencies = .{},
}

@ -1,5 +0,0 @@
.{
.name = "microzig-espressif-esp",
.version = "0.1.0",
.dependencies = .{},
}

@ -1,5 +0,0 @@
.{
.name = "microzig-nordic-nrf5x",
.version = "0.1.0",
.dependencies = .{},
}

@ -262,44 +262,3 @@ pub fn getBootrom(b: *std.Build, rom: BootROM) Stage2Bootloader {
// ); // );
// } // }
// } // }
// pub const Examples = struct {
// adc: *microzig.EmbeddedExecutable,
// blinky: *microzig.EmbeddedExecutable,
// blinky_core1: *microzig.EmbeddedExecutable,
// gpio_clk: *microzig.EmbeddedExecutable,
// i2c_bus_scan: *microzig.EmbeddedExecutable,
// pwm: *microzig.EmbeddedExecutable,
// spi_master: *microzig.EmbeddedExecutable,
// uart: *microzig.EmbeddedExecutable,
// squarewave: *microzig.EmbeddedExecutable,
// //uart_pins: microzig.EmbeddedExecutable,
// flash_program: *microzig.EmbeddedExecutable,
// usb_device: *microzig.EmbeddedExecutable,
// usb_hid: *microzig.EmbeddedExecutable,
// ws2812: *microzig.EmbeddedExecutable,
// random: *microzig.EmbeddedExecutable,
// pub fn init(b: *Build, optimize: std.builtin.OptimizeMode) Examples {
// var ret: Examples = undefined;
// inline for (@typeInfo(Examples).Struct.fields) |field| {
// const path = comptime root() ++ "examples/" ++ field.name ++ ".zig";
// @field(ret, field.name) = addExecutable(b, .{
// .name = field.name,
// .source_file = .{ .path = path },
// .optimize = optimize,
// });
// }
// return ret;
// }
// pub fn install(examples: *Examples, b: *Build) void {
// inline for (@typeInfo(Examples).Struct.fields) |field| {
// b.getInstallStep().dependOn(
// &b.addInstallFileWithDir(@field(examples, field.name).inner.getEmittedBin(), .{ .custom = "firmware" }, field.name ++ ".elf").step,
// );
// }
// }
// };

@ -1,40 +0,0 @@
//! This example takes periodic samples of the temperature sensor and
//! prints it to the UART using the stdlib logging facility.
const std = @import("std");
const microzig = @import("microzig");
const rp2040 = microzig.hal;
const gpio = rp2040.gpio;
const adc = rp2040.adc;
const time = rp2040.time;
const uart = rp2040.uart.num(0);
const baud_rate = 115200;
const uart_tx_pin = gpio.num(0);
const uart_rx_pin = gpio.num(1);
pub const std_options = struct {
pub const logFn = rp2040.uart.log;
};
pub fn main() void {
adc.apply(.{
.temp_sensor_enabled = true,
});
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);
while (true) : (time.sleep_ms(1000)) {
const sample = adc.convert_one_shot_blocking(.temp_sensor) catch {
std.log.err("conversion failed!", .{});
continue;
};
std.log.info("temp value: {}", .{sample});
}
}

@ -1,20 +0,0 @@
const std = @import("std");
const microzig = @import("microzig");
const rp2040 = microzig.hal;
const time = rp2040.time;
const pin_config = rp2040.pins.GlobalConfiguration{
.GPIO25 = .{
.name = "led",
.direction = .out,
},
};
pub fn main() !void {
const pins = pin_config.apply();
while (true) {
pins.led.toggle();
time.sleep_ms(250);
}
}

@ -1,28 +0,0 @@
const std = @import("std");
const microzig = @import("microzig");
const rp2040 = microzig.hal;
const gpio = rp2040.gpio;
const time = rp2040.time;
const multicore = rp2040.multicore;
const led = gpio.num(25);
fn core1() void {
while (true) {
led.put(1);
time.sleep_ms(250);
led.put(0);
time.sleep_ms(250);
}
}
pub fn main() !void {
led.set_function(.sio);
led.set_direction(.out);
multicore.launch_core1(core1);
while (true) {
microzig.cpu.wfi();
}
}

@ -1,81 +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 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 flash_target_offset: u32 = 256 * 1024;
const flash_target_contents = @as([*]const u8, @ptrFromInt(rp2040.flash.XIP_BASE + flash_target_offset));
pub fn panic(message: []const u8, _: ?*std.builtin.StackTrace, _: ?usize) noreturn {
std.log.err("panic: {s}", .{message});
@breakpoint();
while (true) {}
}
pub const std_options = struct {
pub const log_level = .debug;
pub const 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);
var data: [flash.PAGE_SIZE]u8 = undefined;
var i: usize = 0;
var j: u8 = 0;
while (i < flash.PAGE_SIZE) : (i += 1) {
data[i] = j;
if (j == 255) j = 0;
j += 1;
}
std.log.info("Generate data", .{});
std.log.info("data: {s}", .{&data});
// Note that a whole number of sectors (4096 bytes) must be erased at a time
std.log.info("Erasing target region...", .{});
flash.range_erase(flash_target_offset, flash.SECTOR_SIZE);
std.log.info("Done. Read back target region:", .{});
std.log.info("data: {s}", .{flash_target_contents[0..flash.PAGE_SIZE]});
// Note that a whole number of pages (256 bytes) must be written at a time
std.log.info("Programming target region...", .{});
flash.range_program(flash_target_offset, data[0..]);
std.log.info("Done. Read back target region:", .{});
std.log.info("data: {s}", .{flash_target_contents[0..flash.PAGE_SIZE]});
var mismatch: bool = false;
i = 0;
while (i < flash.PAGE_SIZE) : (i += 1) {
if (data[i] != flash_target_contents[i])
mismatch = true;
}
if (mismatch) {
std.log.info("Programming failed!", .{});
} else {
std.log.info("Programming successful!", .{});
}
}

@ -1,16 +0,0 @@
const std = @import("std");
const microzig = @import("microzig");
const rp2040 = microzig.hal;
const gpio = rp2040.gpio;
const clocks = rp2040.clocks;
const gpout0_pin = gpio.num(21);
const clock_config = clocks.GlobalConfiguration.init(.{
.sys = .{ .source = .src_xosc },
.gpout0 = .{ .source = .clk_sys },
});
pub fn main() !void {
gpout0_pin.set_function(.gpck);
while (true) {}
}

@ -1,44 +0,0 @@
const std = @import("std");
const microzig = @import("microzig");
const rp2040 = microzig.hal;
const i2c = rp2040.i2c;
const gpio = rp2040.gpio;
const peripherals = microzig.chip.peripherals;
pub const std_options = struct {
pub const log_level = .info;
pub const logFn = rp2040.uart.log;
};
const uart = rp2040.uart.num(0);
const i2c0 = i2c.num(0);
pub fn main() !void {
uart.apply(.{
.baud_rate = 115200,
.tx_pin = gpio.num(0),
.rx_pin = gpio.num(1),
.clock_config = rp2040.clock_config,
});
rp2040.uart.init_logger(uart);
_ = i2c0.apply(.{
.clock_config = rp2040.clock_config,
.scl_pin = gpio.num(4),
.sda_pin = gpio.num(5),
});
for (0..std.math.maxInt(u7)) |addr| {
const a: i2c.Address = @enumFromInt(addr);
// Skip over any reserved addresses.
if (a.is_reserved()) continue;
var rx_data: [1]u8 = undefined;
_ = i2c0.read_blocking(a, &rx_data) catch continue;
std.log.info("I2C device found at address {X}.", .{addr});
}
}

@ -1,23 +0,0 @@
const std = @import("std");
const microzig = @import("microzig");
const rp2040 = microzig.hal;
const gpio = rp2040.gpio;
const clocks = rp2040.clocks;
const time = rp2040.time;
const regs = microzig.chip.registers;
const multicore = rp2040.multicore;
const pin_config = rp2040.pins.GlobalConfiguration{
.GPIO25 = .{ .name = "led", .function = .PWM4_B },
};
pub fn main() !void {
const pins = pin_config.apply();
pins.led.slice().set_wrap(100);
pins.led.set_level(10);
pins.led.slice().enable();
while (true) {
time.sleep_ms(250);
}
}

@ -1,68 +0,0 @@
//! Example that generates a 4 byte random number every second and outputs the result over UART
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 rand = rp2040.rand;
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);
pub fn panic(message: []const u8, _: ?*std.builtin.StackTrace, _: ?usize) noreturn {
std.log.err("panic: {s}", .{message});
@breakpoint();
while (true) {}
}
pub const std_options = struct {
pub const log_level = .debug;
pub const 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,
});
var ascon = rand.Ascon.init();
var rng = ascon.random();
rp2040.uart.init_logger(uart);
var buffer: [8]u8 = undefined;
var dist: [256]usize = .{0} ** 256;
var counter: usize = 0;
while (true) {
rng.bytes(buffer[0..]);
counter += 8;
for (buffer) |byte| {
dist[@as(usize, @intCast(byte))] += 1;
}
std.log.info("Generate random number: {any}", .{buffer});
if (counter % 256 == 0) {
var i: usize = 0;
std.log.info("Distribution:", .{});
while (i < 256) : (i += 1) {
std.log.info("{} -> {}, {d:2}%", .{ i, dist[i], @as(f32, @floatFromInt(dist[i])) / @as(f32, @floatFromInt(counter)) });
}
}
time.sleep_ms(1000);
}
}

@ -1,29 +0,0 @@
#!/usr/bin/env python3
# Install python3 HID package https://pypi.org/project/hid/
import hid
# default is TinyUSB (0xcafe), Adafruit (0x239a), RaspberryPi (0x2e8a), Espressif (0x303a) VID
USB_VID = (0xcafe, 0x239a, 0x2e8a, 0x303a)
print("VID list: " + ", ".join('%02x' % v for v in USB_VID))
for vid in USB_VID:
for dict in hid.enumerate(vid):
print(dict)
dev = hid.Device(dict['vendor_id'], dict['product_id'])
if dev:
while True:
inp = input("Send text to HID Device : ").encode('utf-8')
dev.write(inp)
x = 0
l = len(inp)
r = b""
while (x < l):
str_in = dev.read(64)
r += str_in
x += 64
print("Received from HID Device:\n", r)
print("hex:\n", r.hex())

@ -1,48 +0,0 @@
#!/usr/bin/env python3
#
# Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
#
# SPDX-License-Identifier: BSD-3-Clause
#
# sudo pip3 install pyusb
import usb.core
import usb.util
# find our device
dev = usb.core.find(idVendor=0x0000, idProduct=0x0001)
# was it found?
if dev is None:
raise ValueError('Device not found')
# get an endpoint instance
cfg = dev.get_active_configuration()
intf = cfg[(0, 0)]
outep = usb.util.find_descriptor(
intf,
# match the first OUT endpoint
custom_match= \
lambda e: \
usb.util.endpoint_direction(e.bEndpointAddress) == \
usb.util.ENDPOINT_OUT)
inep = usb.util.find_descriptor(
intf,
# match the first IN endpoint
custom_match= \
lambda e: \
usb.util.endpoint_direction(e.bEndpointAddress) == \
usb.util.ENDPOINT_IN)
assert inep is not None
assert outep is not None
test_string = "Hello World!"
outep.write(test_string)
from_device = inep.read(len(test_string))
print("Device Says: {}".format(''.join([chr(x) for x in from_device])))

@ -1,26 +0,0 @@
const std = @import("std");
const microzig = @import("microzig");
const rp2040 = microzig.hal;
const time = rp2040.time;
const gpio = rp2040.gpio;
const clocks = rp2040.clocks;
const peripherals = microzig.chip.peripherals;
const BUF_LEN = 0x100;
const spi = rp2040.spi.num(0);
// Communicate with another RP2040 over spi
// Slave implementation: https://github.com/raspberrypi/pico-examples/blob/master/spi/spi_master_slave/spi_slave/spi_slave.c
pub fn main() !void {
spi.apply(.{
.clock_config = rp2040.clock_config,
});
var out_buf: [BUF_LEN]u8 = .{ 0xAA, 0xBB, 0xCC, 0xDD } ** (BUF_LEN / 4);
var in_buf: [BUF_LEN]u8 = undefined;
while (true) {
_ = spi.transceive(&out_buf, &in_buf);
time.sleep_ms(1 * 1000);
}
}

@ -1,84 +0,0 @@
//! Hello world for the PIO module: generating a square wave
const std = @import("std");
const microzig = @import("microzig");
const rp2040 = microzig.hal;
const gpio = rp2040.gpio;
const Pio = rp2040.pio.Pio;
const StateMachine = rp2040.pio.StateMachine;
const squarewave_program = blk: {
@setEvalBranchQuota(2000);
break :blk rp2040.pio.assemble(
\\;
\\; Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
\\;
\\; SPDX-License-Identifier: BSD-3-Clause
\\;
\\.program squarewave
\\ set pindirs, 1 ; Set pin to output
\\again:
\\ set pins, 1 [1] ; Drive pin high and then delay for one cycle
\\ set pins, 0 ; Drive pin low
\\ jmp again ; Set PC to label `again`
, .{}).get_program_by_name("squarewave");
};
// Pick one PIO instance arbitrarily. We're also arbitrarily picking state
// machine 0 on this PIO instance (the state machines are numbered 0 to 3
// inclusive).
const pio: Pio = .pio0;
const sm: StateMachine = .sm0;
pub fn main() void {
pio.gpio_init(gpio.num(2));
pio.sm_load_and_start_program(sm, squarewave_program, .{
.clkdiv = rp2040.pio.ClkDivOptions.from_float(125),
.pin_mappings = .{
.set = .{
.base = 2,
.count = 1,
},
},
}) catch unreachable;
pio.sm_set_enabled(sm, true);
while (true) {}
//// Load the assembled program directly into the PIO's instruction memory.
//// Each PIO instance has a 32-slot instruction memory, which all 4 state
//// machines can see. The system has write-only access.
//for (squarewave_program.instructions, 0..) |insn, i|
// pio.get_instruction_memory()[i] = insn;
//// Configure state machine 0 to run at sysclk/2.5. The state machines can
//// run as fast as one instruction per clock cycle, but we can scale their
//// speed down uniformly to meet some precise frequency target, e.g. for a
//// UART baud rate. This register has 16 integer divisor bits and 8
//// fractional divisor bits.
//pio.sm_set_clkdiv(sm, .{
// .int = 2,
// .frac = 0x80,
//});
//// There are five pin mapping groups (out, in, set, side-set, jmp pin)
//// which are used by different instructions or in different circumstances.
//// Here we're just using SET instructions. Configure state machine 0 SETs
//// to affect GPIO 0 only; then configure GPIO0 to be controlled by PIO0,
//// as opposed to e.g. the processors.
//pio.gpio_init(2);
//pio.sm_set_pin_mappings(sm, .{
// .out = .{
// .base = 2,
// .count = 1,
// },
//});
//// Set the state machine running. The PIO CTRL register is global within a
//// PIO instance, so you can start/stop multiple state machines
//// simultaneously. We're using the register's hardware atomic set alias to
//// make one bit high without doing a read-modify-write on the register.
//pio.sm_set_enabled(sm, true);
//while (true) {}
}

@ -1,49 +0,0 @@
const std = @import("std");
const microzig = @import("microzig");
const rp2040 = microzig.hal;
const time = rp2040.time;
const gpio = rp2040.gpio;
const clocks = rp2040.clocks;
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);
pub fn panic(message: []const u8, _: ?*std.builtin.StackTrace, _: ?usize) noreturn {
std.log.err("panic: {s}", .{message});
@breakpoint();
while (true) {}
}
pub const std_options = struct {
pub const log_level = .debug;
pub const 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);
var i: u32 = 0;
while (true) : (i += 1) {
led.put(1);
std.log.info("what {}", .{i});
time.sleep_ms(500);
led.put(0);
time.sleep_ms(500);
}
}

@ -1,172 +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{
.length = @as(u8, @intCast(@sizeOf(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{
.length = @as(u8, @intCast(@sizeOf(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 = &.{
.length = @as(u8, @intCast(@sizeOf(usb.DeviceDescriptor))),
.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 = &.{
.length = @as(u8, @intCast(@sizeOf(usb.InterfaceDescriptor))),
.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 = &.{
.length = @as(u8, @intCast(@sizeOf(usb.ConfigurationDescriptor))),
.descriptor_type = usb.DescType.Config,
.total_length = @as(u8, @intCast(@sizeOf(usb.ConfigurationDescriptor) + @sizeOf(usb.InterfaceDescriptor) + @sizeOf(usb.EndpointDescriptor) + @sizeOf(usb.EndpointDescriptor))),
.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 std_options = struct {
pub const log_level = .debug;
pub const 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();
}
}
}

@ -1,187 +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{
.length = @as(u8, @intCast(@sizeOf(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{
.length = @as(u8, @intCast(@sizeOf(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,
};
// This is our device configuration
pub var DEVICE_CONFIGURATION: usb.DeviceConfiguration = .{
.device_descriptor = &.{
.length = @as(u8, @intCast(@sizeOf(usb.DeviceDescriptor))),
.descriptor_type = usb.DescType.Device,
.bcd_usb = 0x0200,
.device_class = 0,
.device_subclass = 0,
.device_protocol = 0,
.max_packet_size0 = 64,
.vendor = 0xCafe,
.product = 1,
.bcd_device = 0x0100,
// Those are indices to the descriptor strings
// Make sure to provide enough string descriptors!
.manufacturer_s = 1,
.product_s = 2,
.serial_s = 3,
.num_configurations = 1,
},
.interface_descriptor = &.{
.length = @as(u8, @intCast(@sizeOf(usb.InterfaceDescriptor))),
.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 = &.{
.length = @as(u8, @intCast(@sizeOf(usb.ConfigurationDescriptor))),
.descriptor_type = usb.DescType.Config,
.total_length = @as(u8, @intCast(@sizeOf(usb.ConfigurationDescriptor) + @sizeOf(usb.InterfaceDescriptor) + @sizeOf(usb.EndpointDescriptor) + @sizeOf(usb.EndpointDescriptor))),
.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",
&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,
},
};
pub fn panic(message: []const u8, _: ?*std.builtin.StackTrace, _: ?usize) noreturn {
std.log.err("panic: {s}", .{message});
@breakpoint();
while (true) {}
}
pub const std_options = struct {
pub const log_level = .debug;
pub const 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(
true, // debug output over UART [Y/n]
) catch unreachable;
new = time.get_time_since_boot().to_us();
if (new - old > 500000) {
old = new;
led.toggle();
}
}
}

@ -1,94 +0,0 @@
const std = @import("std");
const microzig = @import("microzig");
const rp2040 = microzig.hal;
const gpio = rp2040.gpio;
const Pio = rp2040.pio.Pio;
const StateMachine = rp2040.pio.StateMachine;
const ws2812_program = blk: {
@setEvalBranchQuota(5000);
break :blk rp2040.pio.assemble(
\\;
\\; Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
\\;
\\; SPDX-License-Identifier: BSD-3-Clause
\\;
\\.program ws2812
\\.side_set 1
\\
\\.define public T1 2
\\.define public T2 5
\\.define public T3 3
\\
\\.wrap_target
\\bitloop:
\\ out x, 1 side 0 [T3 - 1] ; Side-set still takes place when instruction stalls
\\ jmp !x do_zero side 1 [T1 - 1] ; Branch on the bit we shifted out. Positive pulse
\\do_one:
\\ jmp bitloop side 1 [T2 - 1] ; Continue driving high, for a long pulse
\\do_zero:
\\ nop side 0 [T2 - 1] ; Or drive low, for a short pulse
\\.wrap
, .{}).get_program_by_name("ws2812");
};
const pio: Pio = .pio0;
const sm: StateMachine = .sm0;
const led_pin = gpio.num(23);
pub fn main() void {
pio.gpio_init(led_pin);
sm_set_consecutive_pindirs(pio, sm, @intFromEnum(led_pin), 1, true);
const cycles_per_bit: comptime_int = ws2812_program.defines[0].value + //T1
ws2812_program.defines[1].value + //T2
ws2812_program.defines[2].value; //T3
const div = @as(f32, @floatFromInt(rp2040.clock_config.sys.?.output_freq)) /
(800_000 * cycles_per_bit);
pio.sm_load_and_start_program(sm, ws2812_program, .{
.clkdiv = rp2040.pio.ClkDivOptions.from_float(div),
.pin_mappings = .{
.side_set = .{
.base = @intFromEnum(led_pin),
.count = 1,
},
},
.shift = .{
.out_shiftdir = .left,
.autopull = true,
.pull_threshold = 24,
.join_tx = true,
},
}) catch unreachable;
pio.sm_set_enabled(sm, true);
while (true) {
pio.sm_blocking_write(sm, 0x00ff00 << 8); //red
rp2040.time.sleep_ms(1000);
pio.sm_blocking_write(sm, 0xff0000 << 8); //green
rp2040.time.sleep_ms(1000);
pio.sm_blocking_write(sm, 0x0000ff << 8); //blue
rp2040.time.sleep_ms(1000);
}
}
fn sm_set_consecutive_pindirs(_pio: Pio, _sm: StateMachine, pin: u5, count: u3, is_out: bool) void {
const sm_regs = _pio.get_sm_regs(_sm);
const pinctrl_saved = sm_regs.pinctrl.raw;
sm_regs.pinctrl.modify(.{
.SET_BASE = pin,
.SET_COUNT = count,
});
_pio.sm_exec(_sm, rp2040.pio.Instruction{
.tag = .set,
.delay_side_set = 0,
.payload = .{
.set = .{
.data = @intFromBool(is_out),
.destination = .pindirs,
},
},
});
sm_regs.pinctrl.raw = pinctrl_saved;
}

@ -8,13 +8,27 @@ fn buildTools(b: *std.Build) void {
const tools_step = b.step("tools", "Only build the development tools"); const tools_step = b.step("tools", "Only build the development tools");
b.getInstallStep().dependOn(tools_step); b.getInstallStep().dependOn(tools_step);
const eggzon_dep = b.dependency("eggzon", .{});
const eggzon_mod = eggzon_dep.module("eggzon");
const create_build_meta = b.addExecutable(.{
.name = "create-pkg-descriptor",
.root_source_file = .{ .path = "tools/create-pkg-descriptor.zig" },
.optimize = .ReleaseSafe,
});
create_build_meta.addModule("eggzon", eggzon_mod);
installTool(tools_step, create_build_meta);
const archive_info = b.addExecutable(.{ const archive_info = b.addExecutable(.{
.name = "archive-info", .name = "archive-info",
.optimize = .ReleaseSafe, .optimize = .ReleaseSafe,
.root_source_file = .{ .path = "tools/archive-info.zig" }, .root_source_file = .{ .path = "tools/archive-info.zig" },
}); });
installTool(tools_step, archive_info);
}
tools_step.dependOn(&b.addInstallArtifact(archive_info, .{ fn installTool(tools_step: *std.Build.Step, exe: *std.Build.Step.Compile) void {
tools_step.dependOn(&tools_step.owner.addInstallArtifact(exe, .{
.dest_dir = .{ .override = .{ .custom = "tools" } }, .dest_dir = .{ .override = .{ .custom = "tools" } },
}).step); }).step);
} }

@ -0,0 +1,10 @@
.{
.name = "microzig/monorepo",
.version = "0.0.0",
.dependencies = .{
.eggzon = .{
.url = "https://github.com/ziglibs/eggzon/archive/refs/heads/master.tar.gz",
.hash = "1220cd5cec7e9d4911074a9b2dec2dabef76e1adf94d041bca068163ce7666c4be47",
},
},
}

@ -1,29 +0,0 @@
.{
.name = "microzig",
.version = "0.1.0",
.paths = .{
"build.zig",
"build.zig.zon",
"design",
"docs",
"LICENSE",
"README.adoc",
"src",
"test",
"thoughts.md",
},
.dependencies = .{
.uf2 = .{
.url = "https://github.com/ZigEmbeddedGroup/uf2/archive/8037b439ccbac862471392b25e94a8995d784e2c.tar.gz",
.hash = "1220cc66563fc1ecefca7990968441dc9d4db717884ffa9a2de657f60ed4bb74a70a",
},
.regz = .{
.url = "https://github.com/ZigEmbeddedGroup/regz/archive/d66ffd56f51fc46c071412141b5d0c74dc83c310.tar.gz",
.hash = "122002c5f2e31c11373ede6e8a8dd9a61aabd60d38df667ec33b5f994d1f0b503823",
},
.@"umm-zig" = .{
.url = "https://github.com/ZigEmbeddedGroup/umm-zig/archive/99d815adfbc5cc4ad385dd765a6192f85e54179f.tar.gz",
.hash = "12207ef7375ea45e97f4fba9c5dfa74d022902893c4dbf1a0076726b7ec39a02ea3f",
},
},
}

@ -1,4 +1,14 @@
{ {
"package_name": "microzig-build", "package_name": "build",
"package_type": "core" "package_type": "build",
"external_dependencies": {
"uf2": {
"url": "https://github.com/ZigEmbeddedGroup/uf2/archive/8037b439ccbac862471392b25e94a8995d784e2c.tar.gz",
"hash": "1220cc66563fc1ecefca7990968441dc9d4db717884ffa9a2de657f60ed4bb74a70a"
},
"regz": {
"url": "https://github.com/ZigEmbeddedGroup/regz/archive/d66ffd56f51fc46c071412141b5d0c74dc83c310.tar.gz",
"hash": "122002c5f2e31c11373ede6e8a8dd9a61aabd60d38df667ec33b5f994d1f0b503823"
}
}
} }

@ -1,29 +0,0 @@
.{
.name = "microzig",
.version = "0.1.0",
.paths = .{
"build.zig",
"build.zig.zon",
"design",
"docs",
"LICENSE",
"README.adoc",
"src",
"test",
"thoughts.md",
},
.dependencies = .{
.uf2 = .{
.url = "https://github.com/ZigEmbeddedGroup/uf2/archive/8037b439ccbac862471392b25e94a8995d784e2c.tar.gz",
.hash = "1220cc66563fc1ecefca7990968441dc9d4db717884ffa9a2de657f60ed4bb74a70a",
},
.regz = .{
.url = "https://github.com/ZigEmbeddedGroup/regz/archive/d66ffd56f51fc46c071412141b5d0c74dc83c310.tar.gz",
.hash = "122002c5f2e31c11373ede6e8a8dd9a61aabd60d38df667ec33b5f994d1f0b503823",
},
.@"umm-zig" = .{
.url = "https://github.com/ZigEmbeddedGroup/umm-zig/archive/99d815adfbc5cc4ad385dd765a6192f85e54179f.tar.gz",
.hash = "12207ef7375ea45e97f4fba9c5dfa74d022902893c4dbf1a0076726b7ec39a02ea3f",
},
},
}

@ -1,4 +1,10 @@
{ {
"package_name": "microzig", "package_name": "core",
"package_type": "core" "package_type": "core",
"external_dependencies": {
"umm-zig": {
"url": "https://github.com/ZigEmbeddedGroup/umm-zig/archive/99d815adfbc5cc4ad385dd765a6192f85e54179f.tar.gz",
"hash": "12207ef7375ea45e97f4fba9c5dfa74d022902893c4dbf1a0076726b7ec39a02ea3f"
}
}
} }

@ -67,16 +67,16 @@
}, },
"nixpkgs": { "nixpkgs": {
"locked": { "locked": {
"lastModified": 1704290814, "lastModified": 1704766047,
"narHash": "sha256-LWvKHp7kGxk/GEtlrGYV68qIvPHkU9iToomNFGagixU=", "narHash": "sha256-q9tH9yvUWVBh5XpWafpCYAYf72ZyNhfmpgfR4fwM6uw=",
"owner": "nixos", "owner": "nixos",
"repo": "nixpkgs", "repo": "nixpkgs",
"rev": "70bdadeb94ffc8806c0570eb5c2695ad29f0e421", "rev": "cc2f101c016d42b728a9cb8244215a5d2d98f6df",
"type": "github" "type": "github"
}, },
"original": { "original": {
"owner": "nixos", "owner": "nixos",
"ref": "release-23.05", "ref": "release-23.11",
"repo": "nixpkgs", "repo": "nixpkgs",
"type": "github" "type": "github"
} }

@ -2,7 +2,7 @@
description = "microzig development environment"; description = "microzig development environment";
inputs = { inputs = {
nixpkgs.url = "github:nixos/nixpkgs/release-23.05"; nixpkgs.url = "github:nixos/nixpkgs/release-23.11";
flake-utils.url = "github:numtide/flake-utils"; flake-utils.url = "github:numtide/flake-utils";
# required for latest zig # required for latest zig
@ -15,12 +15,13 @@
}; };
}; };
outputs = { outputs =
self, { self
nixpkgs, , nixpkgs
flake-utils, , flake-utils
... , ...
} @ inputs: let } @ inputs:
let
overlays = [ overlays = [
# Other overlays # Other overlays
(final: prev: { (final: prev: {
@ -30,14 +31,67 @@
# Our supported systems are the same supported systems as the Zig binaries # Our supported systems are the same supported systems as the Zig binaries
systems = builtins.attrNames inputs.zig.packages; systems = builtins.attrNames inputs.zig.packages;
# buildenv-python-pkgs = ps: with ps; [
# # ...
# (
# # https://files.pythonhosted.org/packages/26/b4/bd652fbd5cbfa4f149e1630c0da70dc3c37ac27187eb8425eb403bd28a88/dataclasses_json-0.6.3.tar.gz
# buildPythonPackage rec {
# pname = "dataclasses_json";
# version = "0.6.3";
# pyproject = true;
# src = fetchPypi {
# inherit pname version;
# sha256 = "sha256-NctAqugkc2/flZgBNWZBg2NlIZz+FMrrEVw5E293XSo=";
# };
# doCheck = false;
# propagatedBuildInputs = [
# # Specify dependencies
# ps.poetry-dynamic-versioning
# pkgs.poetry
# ps.poetry-core
# ];
# }
# )
# ];
in in
flake-utils.lib.eachSystem systems ( flake-utils.lib.eachSystem systems (
system: let system:
let
pkgs = import nixpkgs { inherit overlays system; }; pkgs = import nixpkgs { inherit overlays system; };
in rec { in
let
python3 = pkgs.python3.override {
self = python3;
packageOverrides = self: super: {
dataclasses_json = self.buildPythonPackage rec {
pname = "dataclasses_json";
format = "pyproject";
version = "0.6.3";
src = self.fetchPypi {
inherit pname version;
sha256 = "sha256-NctAqugkc2/flZgBNWZBg2NlIZz+FMrrEVw5E293XSo=";
};
doCheck = false;
nativeBuildInputs = [ self.poetry-dynamic-versioning self.poetry-core ];
};
};
};
in
rec {
devShells.default = pkgs.mkShell { devShells.default = pkgs.mkShell {
nativeBuildInputs = [ nativeBuildInputs = [
pkgs.zigpkgs."0.11.0" pkgs.zigpkgs."0.11.0"
(python3.withPackages (ps: [
ps.dataclasses_json
ps.marshmallow
ps.typing-inspect
ps.semver
ps.pathspec
]))
]; ];
buildInputs = [ buildInputs = [

@ -0,0 +1,19 @@
const std = @import("std");
pub fn build(b: *std.Build) !void {
const target = b.standardTargetOptions(.{});
const optimize = b.standardOptimizeOption(.{});
const args_dep = b.dependency("args", .{});
const args_mod = args_dep.module("args");
const flash_tool = b.addExecutable(.{
.name = "uf2-flash",
.root_source_file = .{ .path = "src/main.zig" },
.optimize = optimize,
.target = target,
});
flash_tool.addModule("args", args_mod);
b.installArtifact(flash_tool);
}

@ -0,0 +1,333 @@
const std = @import("std");
const args_parser = @import("args");
const builtin = @import("builtin");
const CliOptions = struct {
help: bool = false,
device: ?[]const u8 = null,
wait: bool = false,
pub const shorthands = .{
.h = "help",
.d = "device",
.w = "wait",
};
};
const wait_device_ready_timeout = 60 * std.time.ns_per_s; // timeout until a device is found
const wait_device_avail_timeout = 60 * std.time.ns_per_s; // timeout until a device is found
const access_denied_limit = 20; // try that many times with AccessDenied before the user is informed
fn print_usage(file: std.fs.File, exe: ?[]const u8) !void {
try file.writer().writeAll(exe orelse "uf2-flash");
try file.writer().writeAll(
\\ [-h] [-d <device>] <uf2-file>
\\Flash devices easily via the UF2 interface.
\\
\\Options:
\\ -h, --help Shows this help text.
\\ -d, --device <path> Uses <path> as the UF2 device. Otherwise tries to auto-guess the correct device.
\\ -w, --wait Waits 60 seconds until a device appears.
\\
);
}
pub fn main() !u8 {
const stderr = std.io.getStdErr();
const stdout = std.io.getStdOut();
const stdin = std.io.getStdIn();
var arena = std.heap.ArenaAllocator.init(std.heap.page_allocator);
defer _ = arena.deinit();
const allocator = arena.allocator();
var cli = args_parser.parseForCurrentProcess(CliOptions, allocator, .print) catch return 1;
defer cli.deinit();
if (cli.options.help) {
try print_usage(stdout, cli.executable_name);
return 0;
}
if (cli.positionals.len != 1) {
try print_usage(stderr, cli.executable_name);
return 1;
}
const uf2_file_path = cli.positionals[0];
var uf2_file = try std.fs.cwd().openFile(uf2_file_path, .{});
defer uf2_file.close();
const uf2_stat = try uf2_file.stat();
if ((uf2_stat.size % 512) != 0) {
std.log.warn("{s} does not have a size multiple of 512. might be corrupt!", .{uf2_file_path});
}
const file_valid = blk: {
try uf2_file.seekTo(0);
var file_valid = true;
while (file_valid) {
var block: [512]u8 = undefined;
const len = try uf2_file.read(&block);
if (len == 0)
break;
// 0 4 First magic number, 0x0A324655 ("UF2\n")
// 4 4 Second magic number, 0x9E5D5157
// 8 4 Flags
// 12 4 Address in flash where the data should be written
// 16 4 Number of bytes used in data (often 256)
// 20 4 Sequential block number; starts at 0
// 24 4 Total number of blocks in file
// 28 4 File size or board family ID or zero
// 32 476 Data, padded with zeros
// 508 4 Final magic number, 0x0AB16F30
const first_magic_number = std.mem.readIntLittle(u32, block[0..][0..4]);
const second_magic_number = std.mem.readIntLittle(u32, block[4..][0..4]);
const final_magic_number = std.mem.readIntLittle(u32, block[508..][0..4]);
file_valid = file_valid and (first_magic_number == 0x0A324655);
file_valid = file_valid and (second_magic_number == 0x9E5D5157);
file_valid = file_valid and (final_magic_number == 0x0AB16F30);
// TODO: Use [File size or board family ID or zero] field to determine the way to find the UF2 device.
}
break :blk file_valid;
};
if (file_valid == false) {
std.log.warn("{s} does not seem to be a valid UF2 file. Do you really want to flash it?", .{uf2_file_path});
while (true) {
try stderr.writer().writeAll("Flash? [jN]: ");
var buffer: [64]u8 = undefined;
const selection_or_null = try stdin.reader().readUntilDelimiterOrEof(&buffer, '\n');
const selection_str = std.mem.trim(u8, selection_or_null orelse "", "\r\n\t ");
if (selection_str.len == 0)
return 1;
if (std.ascii.eqlIgnoreCase(selection_str, "j"))
break;
if (std.ascii.eqlIgnoreCase(selection_str, "n"))
return 1;
}
}
try uf2_file.seekTo(0);
const detect_timeout = std.time.nanoTimestamp() + wait_device_avail_timeout;
var first_run = true;
const device_path = if (cli.options.device) |devname|
try allocator.dupe(u8, devname)
else while (true) {
if (std.time.nanoTimestamp() >= detect_timeout) {
try stderr.writeAll("failed to detect any RP2040 devices :(\n");
return 1;
}
const maybe_device = try autoDetectPico(allocator);
if (maybe_device) |device|
break device;
if (!cli.options.wait) {
try stderr.writeAll("failed to detect any RP2040 devices :(\n");
return 1;
}
if (first_run) {
try stderr.writeAll("failed to detect any RP2040 devices, waiting...\n");
first_run = false;
}
std.time.sleep(250 * std.time.ns_per_ms);
};
const connect_timeout = std.time.nanoTimestamp() + wait_device_ready_timeout;
var first_attempt = true;
var access_denied_counter: u32 = 0;
var last_err: anyerror = error.Unknown;
var device_file: std.fs.File = blk: while (std.time.nanoTimestamp() < connect_timeout) {
var device = std.fs.cwd().openFile(device_path, .{ .mode = .write_only }) catch |err| {
last_err = err;
switch (err) {
error.FileNotFound => {}, // just waiting for the device
error.AccessDenied => {
access_denied_counter += 1;
if (access_denied_counter >= access_denied_limit) {
try stderr.writer().print("Could not open {s}: Access denied. Do you have write-access to the device?\n", .{device_path});
return 1;
}
},
else => |e| return e,
}
if (first_attempt) {
try stderr.writer().print("Waiting for {s}.", .{device_path});
first_attempt = false;
} else {
try stderr.writeAll(".");
}
std.time.sleep(250 * std.time.ns_per_ms);
continue;
};
try stderr.writeAll("\n");
break :blk device;
} else {
try stderr.writer().print("\nfailed to connect to {s}: {s}\n", .{ device_path, @errorName(last_err) });
return 1;
};
defer device_file.close();
try stderr.writeAll("Flashing");
{
try uf2_file.seekTo(0);
var block_num: u64 = 0;
while (true) {
try stderr.writeAll(".");
var block: [512]u8 = undefined;
const rd_len = try uf2_file.read(&block);
if (rd_len == 0)
break;
if (rd_len != block.len) {
try stderr.writer().print("\nFailed to read block {}: Only {} bytes read!\n", .{ block_num, rd_len });
return 1;
}
const wr_len = try device_file.write(&block);
if (wr_len != block.len) {
try stderr.writer().print("\nFailed to write block {}: Only {} bytes written!\n", .{ block_num, wr_len });
return 1;
}
block_num += 1;
}
}
try stderr.writeAll("\nDone.\n");
return 0;
}
fn autoDetectPico(allocator: std.mem.Allocator) !?[]const u8 {
switch (builtin.os.tag) {
.linux => {
const stdin = std.io.getStdIn();
const stderr = std.io.getStdErr();
const Device = struct {
name: []const u8,
path: []const u8,
};
var picos = std.ArrayList(Device).init(allocator);
defer picos.deinit();
var base_dir = try std.fs.openIterableDirAbsolute("/sys/block/", .{});
defer base_dir.close();
var iter = base_dir.iterate();
while (try iter.next()) |entry| {
var device_dir = try base_dir.dir.openDir(entry.name, .{});
defer device_dir.close();
const H = struct {
fn isPicoDevice(dir: std.fs.Dir, allo: std.mem.Allocator) !?[]const u8 {
// "/sys/block/*/removable" => "1"
// "/sys/block/*/device/model" => "RP2"
// "/sys/block/*/device/vendor" => "RPI"
var buffer: [64]u8 = undefined;
const removable = std.mem.trim(u8, try dir.readFile("removable", &buffer), "\r\n\t ");
if (!std.mem.eql(u8, removable, "1"))
return null;
const device_model = std.mem.trim(u8, try dir.readFile("device/model", &buffer), "\r\n\t ");
if (!std.mem.eql(u8, device_model, "RP2"))
return null;
const device_vendor = std.mem.trim(u8, try dir.readFile("device/vendor", &buffer), "\r\n\t ");
if (!std.mem.eql(u8, device_vendor, "RPI"))
return null;
const device_id = std.mem.trim(u8, try dir.readFile("dev", &buffer), "\r\n\t ");
return try std.fs.path.join(allo, &.{
"/dev/block", device_id,
});
}
};
const maybe_device = H.isPicoDevice(device_dir, allocator) catch |err| {
if (err != error.FileNotFound and err != error.AccessDenied) {
std.log.err("failed to scan /sys/block/{s}: {s}", .{ entry.name, @errorName(err) });
}
continue;
};
if (maybe_device) |device_path| {
try picos.append(Device{
.name = try allocator.dupe(u8, entry.name),
.path = device_path,
});
}
}
if (picos.items.len == 0) {
return null;
}
var default_selection: usize = 0;
try stderr.writer().writeAll("Select your device:\n");
for (picos.items, 1..) |pico_dev, index| {
try stderr.writer().print("#{d: <2} {s}\n", .{ index, pico_dev.name });
if (default_selection == 0) {
default_selection = index;
}
}
const selection = while (true) {
try stderr.writer().print("Select port [{}]: ", .{default_selection});
var buffer: [64]u8 = undefined;
const selection_or_null = try stdin.reader().readUntilDelimiterOrEof(&buffer, '\n');
const selection_str = std.mem.trim(u8, selection_or_null orelse break default_selection, "\r\n\t ");
if (selection_str.len == 0)
break default_selection;
const selection = std.fmt.parseInt(usize, selection_str, 10) catch continue;
if (selection < 1 or selection > picos.items.len) {
continue;
}
break selection;
};
return picos.items[selection - 1].path;
},
else => {
std.log.warn("Device auto-detection not implemented for {s}", .{@tagName(builtin.os.tag)});
return null;
},
}
}

@ -21,8 +21,14 @@ const JsonInfo = struct {
pub fn main() !void { pub fn main() !void {
var gpa = std.heap.GeneralPurposeAllocator(.{}){}; var gpa = std.heap.GeneralPurposeAllocator(.{}){};
defer _ = gpa.deinit(); defer _ = gpa.deinit();
const allocator = gpa.allocator(); const allocator = gpa.allocator();
var arena_impl = std.heap.ArenaAllocator.init(allocator);
defer arena_impl.deinit();
const arena = arena_impl.allocator();
const argv = try std.process.argsAlloc(allocator); const argv = try std.process.argsAlloc(allocator);
defer std.process.argsFree(allocator, argv); defer std.process.argsFree(allocator, argv);
@ -35,13 +41,13 @@ pub fn main() !void {
var buffered = std.io.bufferedReaderSize(4096, file.reader()); var buffered = std.io.bufferedReaderSize(4096, file.reader());
var decompress = try std.compress.gzip.decompress(allocator, buffered.reader()); // var decompress = try std.compress.gzip.decompress(allocator, buffered.reader());
defer decompress.deinit(); // defer decompress.deinit();
var arc = try Archive.read_from_tar(allocator, decompress.reader(), .{ var arc = try Archive.read_from_tar(arena, buffered.reader(), .{
.strip_components = 0, .strip_components = 0,
}); });
defer arc.deinit(allocator); defer arc.deinit(arena);
{ {
var paths = std.ArrayList([]const u8).init(allocator); var paths = std.ArrayList([]const u8).init(allocator);
@ -197,9 +203,11 @@ const Archive = struct {
if (start + rounded_file_size > end) return error.TarHeadersTooBig; if (start + rounded_file_size > end) return error.TarHeadersTooBig;
start = @as(usize, @intCast(start + rounded_file_size)); start = @as(usize, @intCast(start + rounded_file_size));
}, },
.hard_link => return error.TarUnsupportedFileType, // includes .symlink, .hardlink
.symbolic_link => return error.TarUnsupportedFileType, else => {
else => return error.TarUnsupportedFileType, std.log.err("unsupported tar type ({}) for '{s}'", .{ header.fileType(), unstripped_file_name });
return error.TarUnsupportedFileType;
},
} }
} }

@ -0,0 +1,473 @@
#!/usr/bin/env python3
#
# Prepares a full deployment of MicroZig.
# Creates all packages into /microzig-deploy with the final folder structure.
#
import sys, os, subprocess,datetime, re, shutil, json, hashlib
from pathlib import Path, PurePosixPath
from dataclasses import dataclass, field
from dataclasses_json import dataclass_json, config as dcj_config, Exclude as JsonExclude
from semver import Version
from marshmallow import fields
from enum import Enum as StrEnum
import pathspec
import stat
from marshmallow import fields as mm_fields
from typing import Optional
VERBOSE = False
ALL_FILES_DIR=".data"
REQUIRED_TOOLS = [
"zig",
"git",
# "date",
# "find",
# "jq",
# "mkdir",
# "dirname",
# "realpath",
]
REPO_ROOT = Path(__file__).parent.parent
assert REPO_ROOT.is_dir()
class PackageType(StrEnum):
build = "build"
core = "core"
board_support = "board-support"
@dataclass_json
@dataclass
class Archive:
size: int
sha256sum: str
@dataclass_json
@dataclass
class Package:
hash: str
files: list[str] = field(default_factory=lambda:[])
@dataclass_json
@dataclass
class ExternalDependency:
url: str
hash: str
@dataclass_json
@dataclass
class Timestamp:
unix: str
iso: str
@dataclass_json
@dataclass
class PackageConfiguration:
package_name: str
package_type: PackageType
version: Optional[Version] = field(default=None, metadata=dcj_config(decoder=Version.parse, encoder=Version.__str__, mm_field=fields.String()))
external_dependencies: dict[str,ExternalDependency] = field(default_factory=lambda:dict())
inner_dependencies: set[str] = field(default_factory=lambda:set())
archive: Optional[Archive] = field(default = None)
created: Optional[Timestamp] = field(default = None)
package: Optional[Package] = field(default= None)
# inner fields:
# package_dir: Path = field(default=None, metadata = dcj_config(exclude=JsonExclude.ALWAYS))
PackageSchema = Package.schema()
PackageConfigurationSchema = PackageConfiguration.schema()
def file_digest(path: Path, hashfunc) -> bytes:
BUF_SIZE = 65536
digest = hashfunc()
with path.open('rb') as f:
while True:
data = f.read(BUF_SIZE)
if not data:
break
digest.update(data)
return digest.digest()
FILE_STAT_MAP = {
stat.S_IFDIR: "directory",
stat.S_IFCHR: "character device",
stat.S_IFBLK: "block device",
stat.S_IFREG: "regular",
stat.S_IFIFO: "fifo",
stat.S_IFLNK: "link",
stat.S_IFSOCK: "socket",
}
def file_type(path: Path) -> str:
return FILE_STAT_MAP[stat.S_IFMT( path.stat().st_mode)]
def execute_raw(*args,hide_stderr = False,**kwargs):
args = [ str(f) for f in args]
if VERBOSE:
print(*args)
res = subprocess.run(args, **kwargs, check=False)
if res.stderr is not None and (not hide_stderr or res.returncode != 0):
sys.stderr.buffer.write(res.stderr)
if res.returncode != 0:
sys.stderr.write(f"command {' '.join(args)} failed with exit code {res.returncode}")
res.check_returncode()
return res
def execute(*args,**kwargs):
execute_raw(*args, **kwargs, capture_output=False)
def slurp(*args, **kwargs):
res = execute_raw(*args, **kwargs, capture_output=True)
return res.stdout
def check_required_tools():
for tool in REQUIRED_TOOLS:
slurp("which", tool)
def check_zig_version(expected):
actual = slurp("zig", "version")
if actual.strip() != expected.encode():
raise RuntimeError(f"Unexpected zig version! Expected {expected}, but found {actual.strip()}!")
def build_zig_tools():
# ensure we have our tools available:
execute("zig", "build", "tools", cwd=REPO_ROOT)
archive_info = REPO_ROOT / "zig-out/tools/archive-info"
create_pkg_descriptor = REPO_ROOT / "zig-out/tools/create-pkg-descriptor"
assert archive_info.is_file()
assert create_pkg_descriptor.is_file()
return {
"archive_info": archive_info,
"create_pkg_descriptor": create_pkg_descriptor,
}
# Determines the correct version:
def get_version_from_git() -> str:
raw_git_out = slurp("git", "describe", "--match", "*.*.*", "--tags", "--abbrev=9", cwd=REPO_ROOT).strip().decode()
def render_version(major,minor,patch,counter,hash):
return f"{major}.{minor}.{patch}-{counter}-{hash}"
full_version = re.match('^([0-9]+)\.([0-9]+)\.([0-9]+)\-([0-9]+)\-([a-z0-9]+)$', raw_git_out)
if full_version:
return render_version(*full_version.groups())
base_version = re.match('^([0-9]+)\.([0-9]+)\.([0-9]+)$', raw_git_out)
if base_version:
commit_hash = slurp("git", "rev-parse", "--short=9", "HEAD")
return render_version(*base_version.groups(), 0, commit_hash)
raise RuntimeError(f"Bad result '{raw_git_out}' from git describe.")
def create_output_directory(repo_root: Path) -> Path:
deploy_target=repo_root / "microzig-deploy"
if deploy_target.is_dir():
shutil.rmtree(deploy_target)
assert not deploy_target.exists()
deploy_target.mkdir()
return deploy_target
def resolve_dependency_order(packages: dict[PackageConfiguration]) -> list[PackageConfiguration]:
open_list = list(packages.values())
closed_set = set()
closed_list = []
while len(open_list) > 0:
head = open_list.pop(0)
all_resolved = True
for dep_name in head.inner_dependencies:
dep = packages[dep_name]
if dep.package_name not in closed_set:
all_resolved = False
break
if all_resolved:
closed_set.add(head.package_name)
closed_list.append(head)
else:
open_list.append(head)
return closed_list
def get_batch_timestamp():
render_time = datetime.datetime.now()
return Timestamp(
unix=str(int(render_time.timestamp())),
iso=render_time.isoformat(),
)
def main():
check_required_tools()
check_zig_version("0.11.0")
print("preparing environment...")
deploy_target = create_output_directory(REPO_ROOT)
# Some generic meta information:
batch_timestamp = get_batch_timestamp()
version = get_version_from_git()
tools = build_zig_tools()
# After building the tools, zig-cache should exist, so we can tap into it for our own caching purposes:
cache_root = REPO_ROOT / "zig-cache"
assert cache_root.is_dir()
cache_dir = cache_root / "microzig"
cache_root.mkdir(exist_ok=True)
# Prepare `.gitignore` pattern matcher:
global_ignore_spec = pathspec.PathSpec.from_lines(
pathspec.patterns.GitWildMatchPattern,
(REPO_ROOT / ".gitignore").read_text().splitlines(),
)
# also insert a pattern to exclude
global_ignore_spec.patterns.append(
pathspec.patterns.GitWildMatchPattern("microzig-package.json")
)
print(global_ignore_spec)
# Fetch and find all packages:
print("validating packages...")
packages = {}
validation_ok = True
for meta_path in REPO_ROOT.rglob("microzig-package.json"):
assert meta_path.is_file()
pkg_dir = meta_path.parent
pkg_dict = json.loads(meta_path.read_bytes())
pkg = PackageConfigurationSchema.load(pkg_dict)
pkg.version = version
pkg.created = batch_timestamp
pkg.package_dir = pkg_dir
if pkg.package_type == PackageType.core:
pass
elif pkg.package_type == PackageType.build:
pass
elif pkg.package_type == PackageType.board_support:
pkg.inner_dependencies.add("core") # BSPs implicitly depend on the core "microzig" package
else:
assert False
buildzig_path = pkg_dir / "build.zig"
buildzon_path = pkg_dir / "build.zig.zon"
if not buildzig_path.is_file():
print("")
print(f"The package at {meta_path} is missing its build.zig file: {buildzig_path}")
print("Please create a build.zig for that package!")
validation_ok = False
if buildzon_path.is_file():
print("")
print(f"The package at {meta_path} has a build.zig.zon: {buildzon_path}")
print("Please remove that file and merge it into microzig-package.json!")
validation_ok = False
if pkg.package_name not in packages:
packages[pkg.package_name] = pkg
else:
print("")
print(f"The package at {meta_path} has a duplicate package name {pkg.package_name}")
print("Please remove that file and merge it into microzig-package.json!")
validation_ok = False
# print("%d\t%s\n", "${pkg_prio}" "${reldir}" >> "${cache_dir}/packages.raw")
# cat "${cache_dir}/packages.raw" | sort | cut -f 2 > "${cache_dir}/packages.list"
if not validation_ok:
print("Not all packages are valid. Fix the packages and try again!" )
exit(1)
print("loaded packages:")
for key in packages:
print(f" * {key}")
print("resolving inner dependencies...")
evaluation_ordered_packages = resolve_dependency_order(packages)
# bundle everything:
print("creating packages...")
for pkg in evaluation_ordered_packages:
print(f"bundling {pkg.package_name}...")
pkg_dir = pkg.package_dir
pkg_cache_dir = cache_dir / hashlib.md5(pkg.package_name.encode()).hexdigest()
pkg_cache_dir.mkdir(exist_ok=True)
meta_path = pkg_dir / "microzig-package.json"
pkg_zon_file = pkg_cache_dir / "build.zig.zon"
out_rel_dir: PurePosixPath
out_basename: str
extra_json: dict = {}
if pkg.package_type == PackageType.build:
out_rel_dir = PurePosixPath(".")
out_basename = pkg.package_name
elif pkg.package_type == PackageType.core:
out_rel_dir = PurePosixPath(".")
out_basename = pkg.package_name
elif pkg.package_type == PackageType.board_support:
parsed_pkg_name = PurePosixPath(pkg.package_name)
out_rel_dir = "board-support" / parsed_pkg_name.parent
out_basename = parsed_pkg_name.name
bsp_info = slurp(
"zig", "build-exe",
f"{REPO_ROOT}/tools/extract-bsp-info.zig" ,
"--cache-dir", f"{REPO_ROOT}/zig-cache",
"--deps", "bsp,microzig",
"--mod", f"bsp:microzig:{pkg_dir}/build.zig",
"--mod", f"microzig:uf2:{REPO_ROOT}/core/build.zig",
"--mod", f"uf2::{REPO_ROOT}/tools/lib/dummy_uf2.zig",
"--name", "extract-bsp-info",
cwd=pkg_cache_dir,
)
extra_json_str=slurp(pkg_cache_dir/"extract-bsp-info")
extra_json = json.loads(extra_json_str)
else:
assert False
assert out_rel_dir is not None
assert out_basename is not None
assert isinstance(extra_json, dict)
# File names:
out_file_name_tar = f"{out_basename}-{version}.tar"
out_file_name_compr = f"{out_file_name_tar}.gz"
out_file_name_meta = f"{out_basename}-{version}.json"
out_symlink_pkg_name = f"{out_basename}.tar.gz"
out_symlink_meta_name = f"{out_basename}.json"
# Directories_:
out_base_dir = deploy_target / out_rel_dir
out_data_dir = out_base_dir / ALL_FILES_DIR
# paths:
out_file_tar = out_data_dir / out_file_name_tar
out_file_targz = out_data_dir / out_file_name_compr
out_file_meta = out_data_dir / out_file_name_meta
out_symlink_pkg = out_base_dir / out_symlink_pkg_name
out_symlink_meta = out_base_dir / out_symlink_meta_name
# ensure the directories exist:
out_base_dir.mkdir(parents = True, exist_ok=True)
out_data_dir.mkdir(parents = True, exist_ok=True)
# find files that should be packaged:
package_files = [*global_ignore_spec.match_tree(pkg_dir,negate = True )]
# package_files = [
# file.relative_to(pkg_dir)
# for file in pkg_dir.rglob("*")
# if not global_ignore_spec.match_file(str(file))
# if file.name !=
# ]
if VERBOSE:
print("\n".join(f" * {str(f)} ({file_type(pkg_dir / f)})" for f in package_files))
print()
# tar -cf "${out_tar}" $(git ls-files -- . ':!:microzig-package.json')
execute("tar", "-cf", out_file_tar, "--hard-dereference", *package_files, cwd=pkg_dir)
zon_data = slurp(
tools["create_pkg_descriptor"], version, out_rel_dir,
input=PackageConfigurationSchema.dumps(pkg).encode(),
)
with pkg_zon_file.open("wb") as f:
f.write(zon_data)
slurp("zig", "fmt", pkg_zon_file) # slurp the message away
execute("tar", "-rf", out_file_tar, "--hard-dereference", pkg_zon_file.name, cwd=pkg_zon_file.parent)
# tar --list --file "${out_tar}" > "${pkg_cache_dir}/contents.list"
zig_pkg_info_str = slurp(tools["archive_info"], out_file_tar)
pkg.package = PackageSchema.loads(zig_pkg_info_str)
# explicitly use maximum compression level here as we're shipping to potentially many people
execute("gzip", "-f9", out_file_tar)
assert not out_file_tar.exists()
assert out_file_targz.is_file()
del out_file_tar
pkg.archive = Archive(
sha256sum = file_digest(out_file_targz, hashlib.sha256).hex(),
size = str(out_file_targz.stat().st_size),
)
with out_file_meta.open("w") as f:
f.write(PackageConfigurationSchema.dumps(pkg))
out_symlink_pkg.symlink_to(out_file_targz.relative_to(out_symlink_pkg.parent))
out_symlink_meta.symlink_to(out_file_meta.relative_to(out_symlink_meta.parent))
# TODO: Verify that each package can be unpacked and built
if __name__ == "__main__":
main()

@ -1,169 +0,0 @@
#!/bin/sh
#
# Prepares a full deployment of MicroZig.
# Creates all packages into /microzig-deploy with the final folder structure.
#
set -eu
all_files_dir=".data"
# test for all required tools:
which zig date find jq mkdir dirname realpath > /dev/null
[ "$(zig version)" = "0.11.0" ]
repo_root="$(dirname "$(dirname "$(realpath "$0")")")"
[ -d "${repo_root}" ]
echo "preparing environment..."
alias create_package="${repo_root}/tools/create-package.sh"
# Some generic meta information:
unix_timestamp="$(date '+%s')"
iso_timestamp="$(date --iso-8601=seconds)"
# Determine correct version:
git_description="$(git describe --match "*.*.*" --tags --abbrev=9)"
version=""
# render-version <major> <minor> <patch> <counter> <hash>
render_version()
{
[ "$#" -eq 5 ]
echo "$1.$2.$3-$4-$5"
}
case "${git_description}" in
*.*.*-*-*)
version="$(render_version $(echo "${git_description}" | sed -E 's/^([0-9]+)\.([0-9]+)\.([0-9]+)\-([0-9]+)\-([a-z0-9]+)$/\1 \2 \3 \4 \5/'))"
;;
*.*.*)
# a "on point" tagged version still has a hash as well as the counter 0!
version="$(render_version $(echo "${git_description}" | sed -E 's/^([0-9]+)\.([0-9]+)\.([0-9]+)$/\1 \2 \3/') 0 $(git rev-parse --short=9 HEAD))"
;;
*)
echo "Bad result '${git_description}' from git describe." >&2
exit 1
;;
esac
if [ -z "${version}" ]; then
echo "Could not determine a version. Please verify repository state!" >&2
exit 1
fi
deploy_target="${repo_root}/microzig-deploy"
[ -d "${deploy_target}" ] && rm -r "${deploy_target}"
mkdir -p "${deploy_target}"
cd "${repo_root}"
# ensure we have our tools available:
zig build tools
[ -x "${repo_root}/zig-out/tools/archive-info" ]
alias archive_info="${repo_root}/zig-out/tools/archive-info"
for dir in $(find -type f -name microzig-package.json -exec dirname '{}' ';'); do
dir="$(realpath "${dir}")"
meta_path="$(realpath "${dir}/microzig-package.json")"
pkg_name="$(jq -r .package_name < "${meta_path}")"
pkg_type="$(jq -r .package_type < "${meta_path}")"
(
cd "${dir}"
echo "bundling ${dir}..."
out_dir=""
out_basename=""
extra_json="{}"
case "${pkg_type}" in
core)
out_dir="${deploy_target}"
out_basename="${pkg_name}"
;;
board-support)
out_dir="${deploy_target}/board-support/$(dirname "${pkg_name}")"
out_basename="$(basename "${pkg_name}")"
extra_json="$(
zig run \
"${repo_root}/tools/extract-bsp-info.zig" \
--cache-dir "${repo_root}/zig-cache" \
--deps bsp,microzig \
--mod "bsp:microzig:${dir}/build.zig" \
--mod "microzig:uf2:${repo_root}/core/build.zig" \
--mod "uf2::${repo_root}/tools/lib/dummy_uf2.zig" \
)"
;;
*)
echo "Unsupported package type: '${pkg_type}'!" >&2
exit 1
;;
esac
[ ! -z "${out_dir}" ] && [ ! -z "${out_basename}" ]
out_fullname="${out_basename}-${version}.tar.gz"
out_fullmeta="${out_basename}-${version}.json"
out_name="${out_basename}.tar.gz"
out_meta="${out_basename}.json"
out_path="${out_dir}/${all_files_dir}/${out_fullname}"
mkdir -p "${out_dir}/${all_files_dir}"
# first, compile package
create_package "${dir}" "${out_path}"
# get some required metadata
file_hash="$(sha256sum "${out_path}" | cut -d " " -f 1)"
file_size="$(stat --format="%s" "${out_path}")"
pkg_info="$(archive_info ${out_path})"
jq \
--arg vers "${version}" \
--arg ts_unix "${unix_timestamp}" \
--arg ts_iso "${iso_timestamp}" \
--arg fhash "${file_hash}" \
--arg fsize "${file_size}" \
--argjson pkg "${pkg_info}" \
--argjson extra "${extra_json}" \
'. + $extra + {
version: $vers,
created: {
unix: $ts_unix,
iso: $ts_iso,
},
archive: {
size: $fsize,
sha256sum: $fhash,
},
package: $pkg
}' \
"${meta_path}" \
> "${out_dir}/${all_files_dir}/${out_fullmeta}" \
(
cd "${out_dir}"
ln -s "${all_files_dir}/${out_fullname}" "${out_name}"
ln -s "${all_files_dir}/${out_fullmeta}" "${out_meta}"
)
)
done

@ -0,0 +1,122 @@
const std = @import("std");
const eggzon = @import("eggzon");
const fmtEscapes = std.zig.fmtEscapes;
const fmtId = std.zig.fmtId;
const Archive = struct {
sha256sum: []const u8,
size: []const u8,
};
const Package = struct {
hash: []const u8,
files: []const []const u8,
};
const Timestamp = struct {
iso: []const u8,
unix: []const u8,
};
const MetaData = struct {
const Type = enum {
@"board-support",
core,
build,
};
package_name: []const u8,
package_type: Type,
version: []const u8,
inner_dependencies: []const []const u8 = &.{},
external_dependencies: std.json.Value = .null,
archive: ?Archive = null,
package: ?Package = null,
created: ?Timestamp = null,
};
// create-pkg-descriptor <version>
pub fn main() !void {
var gpa = std.heap.GeneralPurposeAllocator(.{}){};
defer _ = gpa.deinit();
const allocator = gpa.allocator();
var arena_impl = std.heap.ArenaAllocator.init(allocator);
defer arena_impl.deinit();
const arena = arena_impl.allocator();
const argv = try std.process.argsAlloc(arena);
if (argv.len != 3) {
@panic("version and/or relpath missing!");
}
// System configuration:
const deployment_base_url = "https://download.microzig.tech/packages"; // TODO: Make those configurable
// build inputs:
const version_string = argv[1];
const rel_pkg_path = argv[2];
const version = try std.SemanticVersion.parse(version_string);
const json_input = try std.io.getStdIn().readToEndAlloc(arena, 1 << 20);
errdefer std.log.err("failed to parse json from {s}", .{json_input});
const metadata = try std.json.parseFromSliceLeaky(MetaData, arena, json_input, .{});
var buffered_stdout = std.io.bufferedWriter(std.io.getStdOut().writer());
const stdout = buffered_stdout.writer();
{
try stdout.writeAll(".{\n");
try stdout.print(" .name = \"{}\",\n", .{fmtEscapes(metadata.package_name)});
try stdout.print(" .version = \"{}\",\n", .{version});
try stdout.writeAll(" .dependencies = .{\n");
if (metadata.external_dependencies != .null) {
const deps = &metadata.external_dependencies.object;
for (deps.keys(), deps.values()) |key, value| {
const dep: *const std.json.ObjectMap = &value.object;
//
try stdout.print(" .{} = .{{\n", .{fmtId(key)});
try stdout.print(" .url = \"{}\",\n", .{fmtEscapes(dep.get("url").?.string)});
try stdout.print(" .hash = \"{}\",\n", .{fmtEscapes(dep.get("hash").?.string)});
try stdout.writeAll(" },\n");
}
}
switch (metadata.package_type) {
.core => {
// core packages are always "standalone" in the microzig environment and provide the root
// of the build
},
.build => {
//
},
.@"board-support" => {
// bsp packages implicitly depend on the "microzig" package:
try stdout.writeAll(" .microzig = .{\n");
try stdout.print(" .url = \"{}/{}\",\n", .{ fmtEscapes(deployment_base_url), fmtEscapes(rel_pkg_path) });
try stdout.print(" .hash = \"{}\",\n", .{fmtEscapes("???")});
try stdout.writeAll(" },\n");
},
}
try stdout.writeAll(" },\n");
try stdout.writeAll("}\n");
}
try buffered_stdout.flush();
}
Loading…
Cancel
Save