From c1c19d221e85845e3874d39e8bc7597f54f59237 Mon Sep 17 00:00:00 2001 From: Matt Knight Date: Wed, 26 Apr 2023 01:02:09 -0700 Subject: [PATCH] Gpio api (#51) * improve GPIO API * fix test, update microzig * first DMA functions, new abstraction for enumerating peripherals * rebase main * fix call to reset() --- examples/adc.zig | 18 +-- examples/blinky_core1.zig | 10 +- examples/flash_program.zig | 16 +-- examples/gpio_clk.zig | 9 +- examples/random.zig | 16 +-- examples/spi_master.zig | 3 +- examples/squarewave.zig | 103 +++++++++------ examples/uart.zig | 20 ++- examples/usb_device.zig | 18 ++- examples/usb_hid.zig | 18 ++- src/hal.zig | 34 +++-- src/hal/adc.zig | 5 +- src/hal/dma.zig | 131 ++++++++++++++++++ src/hal/gpio.zig | 198 ++++++++++++++++++---------- src/hal/hw.zig | 37 +++++- src/hal/pins.zig | 27 ++-- src/hal/pio.zig | 156 +++++++++++++--------- src/hal/pio/assembler.zig | 4 +- src/hal/pio/assembler/encoder.zig | 17 ++- src/hal/pio/assembler/tokenizer.zig | 8 +- src/hal/pll.zig | 2 +- src/hal/resets.zig | 150 ++++++++++++++++----- src/hal/spi.zig | 50 +++---- src/hal/uart.zig | 55 ++++---- src/hal/usb.zig | 4 +- 25 files changed, 717 insertions(+), 392 deletions(-) create mode 100644 src/hal/dma.zig diff --git a/examples/adc.zig b/examples/adc.zig index 5d8f0c3..b6d6bf4 100644 --- a/examples/adc.zig +++ b/examples/adc.zig @@ -3,26 +3,22 @@ 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 temp_sensor: adc.Input = .temperature_sensor; -const uart_id = 0; +const uart = rp2040.uart.num(0); const baud_rate = 115200; -const uart_tx_pin = 0; -const uart_rx_pin = 1; +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 init() void { - rp2040.clock_config.apply(); - rp2040.gpio.reset(); - adc.init(); - temp_sensor.init(); - - const uart = rp2040.uart.UART.init(uart_id, .{ +pub fn main() void { + uart.apply(.{ .baud_rate = baud_rate, .tx_pin = uart_tx_pin, .rx_pin = uart_rx_pin, @@ -30,9 +26,7 @@ pub fn init() void { }); rp2040.uart.init_logger(uart); -} -pub fn main() void { while (true) : (time.sleep_ms(1000)) { const sample = temp_sensor.read(); std.log.info("temp value: {}", .{sample}); diff --git a/examples/blinky_core1.zig b/examples/blinky_core1.zig index b3fdd04..64f0674 100644 --- a/examples/blinky_core1.zig +++ b/examples/blinky_core1.zig @@ -6,21 +6,19 @@ const gpio = rp2040.gpio; const time = rp2040.time; const multicore = rp2040.multicore; -const led = 25; +const led = gpio.num(25); fn core1() void { while (true) { - gpio.put(led, 1); + led.put(1); time.sleep_ms(250); - gpio.put(led, 0); + led.put(0); time.sleep_ms(250); } } pub fn main() !void { - gpio.init(led); - gpio.set_direction(led, .out); - + led.set_direction(.out); multicore.launch_core1(core1); while (true) { diff --git a/examples/flash_program.zig b/examples/flash_program.zig index 2fc5cc0..a2999c9 100644 --- a/examples/flash_program.zig +++ b/examples/flash_program.zig @@ -7,11 +7,11 @@ const time = rp2040.time; const gpio = rp2040.gpio; const clocks = rp2040.clocks; -const led = 25; -const uart_id = 0; +const led = gpio.num(25); +const uart = rp2040.uart.num(0); const baud_rate = 115200; -const uart_tx_pin = 0; -const uart_rx_pin = 1; +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 = @intToPtr([*]const u8, rp2040.flash.XIP_BASE + flash_target_offset); @@ -28,12 +28,10 @@ pub const std_options = struct { }; pub fn main() !void { - gpio.reset(); - gpio.init(led); - gpio.set_direction(led, .out); - gpio.put(led, 1); + led.set_direction(.out); + led.put(1); - const uart = rp2040.uart.UART.init(uart_id, .{ + uart.apply(.{ .baud_rate = baud_rate, .tx_pin = uart_tx_pin, .rx_pin = uart_rx_pin, diff --git a/examples/gpio_clk.zig b/examples/gpio_clk.zig index e66761c..dd28102 100644 --- a/examples/gpio_clk.zig +++ b/examples/gpio_clk.zig @@ -4,18 +4,13 @@ const rp2040 = microzig.hal; const gpio = rp2040.gpio; const clocks = rp2040.clocks; -const gpout0_pin = 21; +const gpout0_pin = gpio.num(21); const clock_config = clocks.GlobalConfiguration.init(.{ .sys = .{ .source = .src_xosc }, .gpout0 = .{ .source = .clk_sys }, }); -pub fn init() void { - clock_config.apply(); - gpio.reset(); -} - pub fn main() !void { - gpio.set_function(gpout0_pin, .gpck); + gpout0_pin.set_function(.gpck); while (true) {} } diff --git a/examples/random.zig b/examples/random.zig index dbf00d5..0645839 100644 --- a/examples/random.zig +++ b/examples/random.zig @@ -10,11 +10,11 @@ const gpio = rp2040.gpio; const clocks = rp2040.clocks; const rand = rp2040.rand; -const led = 25; -const uart_id = 0; +const led = gpio.num(25); +const uart = rp2040.uart.num(0); const baud_rate = 115200; -const uart_tx_pin = 0; -const uart_rx_pin = 1; +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}); @@ -28,12 +28,10 @@ pub const std_options = struct { }; pub fn main() !void { - gpio.reset(); - gpio.init(led); - gpio.set_direction(led, .out); - gpio.put(led, 1); + led.set_direction(.out); + led.put(1); - const uart = rp2040.uart.UART.init(uart_id, .{ + uart.apply(.{ .baud_rate = baud_rate, .tx_pin = uart_tx_pin, .rx_pin = uart_rx_pin, diff --git a/examples/spi_master.zig b/examples/spi_master.zig index ba1c0c2..c160fee 100644 --- a/examples/spi_master.zig +++ b/examples/spi_master.zig @@ -8,11 +8,12 @@ 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 { - const spi = rp2040.spi.SPI.init(0, .{ + spi.apply(.{ .clock_config = rp2040.clock_config, }); var out_buf: [BUF_LEN]u8 = .{ 0xAA, 0xBB, 0xCC, 0xDD } ** (BUF_LEN / 4); diff --git a/examples/squarewave.zig b/examples/squarewave.zig index 7437000..0564b62 100644 --- a/examples/squarewave.zig +++ b/examples/squarewave.zig @@ -6,57 +6,76 @@ const gpio = rp2040.gpio; const Pio = rp2040.pio.Pio; const StateMachine = rp2040.pio.StateMachine; -const squarewave_program = (rp2040.pio.assemble( +const squarewave_program = 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` -, .{}) catch - @panic("failed to assemble program")) - .get_program_by_name("squarewave"); +, .{}).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 { - gpio.reset(); - // 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; - - // 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(0); - pio.sm_set_pin_mappings(sm, .{ - .out = .{ - .base = 0, - .count = 1, + 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; - // 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) {} + + //// 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) {} } diff --git a/examples/uart.zig b/examples/uart.zig index 57cf1c4..6be3b38 100644 --- a/examples/uart.zig +++ b/examples/uart.zig @@ -6,11 +6,11 @@ const time = rp2040.time; const gpio = rp2040.gpio; const clocks = rp2040.clocks; -const led = 25; -const uart_id = 0; +const led = gpio.num(25); +const uart = rp2040.uart.num(0); const baud_rate = 115200; -const uart_tx_pin = 0; -const uart_rx_pin = 1; +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}); @@ -24,12 +24,10 @@ pub const std_options = struct { }; pub fn main() !void { - gpio.reset(); - gpio.init(led); - gpio.set_direction(led, .out); - gpio.put(led, 1); + led.set_direction(.out); + led.put(1); - const uart = rp2040.uart.UART.init(uart_id, .{ + uart.apply(.{ .baud_rate = baud_rate, .tx_pin = uart_tx_pin, .rx_pin = uart_rx_pin, @@ -40,11 +38,11 @@ pub fn main() !void { var i: u32 = 0; while (true) : (i += 1) { - gpio.put(led, 1); + led.put(1); std.log.info("what {}", .{i}); time.sleep_ms(500); - gpio.put(led, 0); + led.put(0); time.sleep_ms(500); } } diff --git a/examples/usb_device.zig b/examples/usb_device.zig index c86d5e1..3395286 100644 --- a/examples/usb_device.zig +++ b/examples/usb_device.zig @@ -8,11 +8,11 @@ const gpio = rp2040.gpio; const clocks = rp2040.clocks; const usb = rp2040.usb; -const led = 25; -const uart_id = 0; +const led = gpio.num(25); +const uart = rp2040.uart.num(0); const baud_rate = 115200; -const uart_tx_pin = 0; -const uart_rx_pin = 1; +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 { @@ -138,12 +138,10 @@ pub const std_options = struct { }; pub fn main() !void { - gpio.reset(); - gpio.init(led); - gpio.set_direction(led, .out); - gpio.put(led, 1); + led.set_direction(.out); + led.put(1); - const uart = rp2040.uart.UART.init(uart_id, .{ + uart.apply(.{ .baud_rate = baud_rate, .tx_pin = uart_tx_pin, .rx_pin = uart_rx_pin, @@ -167,7 +165,7 @@ pub fn main() !void { new = time.get_time_since_boot().us_since_boot; if (new - old > 500000) { old = new; - gpio.toggle(led); + led.toggle(); } } } diff --git a/examples/usb_hid.zig b/examples/usb_hid.zig index 633add7..051ad74 100644 --- a/examples/usb_hid.zig +++ b/examples/usb_hid.zig @@ -8,11 +8,11 @@ const gpio = rp2040.gpio; const clocks = rp2040.clocks; const usb = rp2040.usb; -const led = 25; -const uart_id = 0; +const led = gpio.num(25); +const uart = rp2040.uart.num(0); const baud_rate = 115200; -const uart_tx_pin = 0; -const uart_rx_pin = 1; +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 { @@ -153,12 +153,10 @@ pub const std_options = struct { }; pub fn main() !void { - gpio.reset(); - gpio.init(led); - gpio.set_direction(led, .out); - gpio.put(led, 1); + led.set_direction(.out); + led.put(1); - const uart = rp2040.uart.UART.init(uart_id, .{ + uart.apply(.{ .baud_rate = baud_rate, .tx_pin = uart_tx_pin, .rx_pin = uart_rx_pin, @@ -182,7 +180,7 @@ pub fn main() !void { new = time.get_time_since_boot().us_since_boot; if (new - old > 500000) { old = new; - gpio.toggle(led); + led.toggle(); } } } diff --git a/src/hal.zig b/src/hal.zig index c9ac986..89e2b58 100644 --- a/src/hal.zig +++ b/src/hal.zig @@ -3,21 +3,22 @@ const microzig = @import("microzig"); const SIO = microzig.chip.peripherals.SIO; pub const adc = @import("hal/adc.zig"); -pub const pins = @import("hal/pins.zig"); -pub const gpio = @import("hal/gpio.zig"); pub const clocks = @import("hal/clocks.zig"); +pub const dma = @import("hal/dma.zig"); +pub const flash = @import("hal/flash.zig"); +pub const gpio = @import("hal/gpio.zig"); +pub const irq = @import("hal/irq.zig"); pub const multicore = @import("hal/multicore.zig"); -pub const time = @import("hal/time.zig"); -pub const uart = @import("hal/uart.zig"); +pub const pins = @import("hal/pins.zig"); +pub const pio = @import("hal/pio.zig"); pub const pwm = @import("hal/pwm.zig"); -pub const spi = @import("hal/spi.zig"); +pub const rand = @import("hal/random.zig"); pub const resets = @import("hal/resets.zig"); -pub const irq = @import("hal/irq.zig"); pub const rom = @import("hal/rom.zig"); -pub const flash = @import("hal/flash.zig"); -pub const pio = @import("hal/pio.zig"); +pub const spi = @import("hal/spi.zig"); +pub const time = @import("hal/time.zig"); +pub const uart = @import("hal/uart.zig"); pub const usb = @import("hal/usb.zig"); -pub const rand = @import("hal/random.zig"); pub const clock_config = clocks.GlobalConfiguration.init(.{ .ref = .{ .source = .src_xosc }, @@ -32,7 +33,22 @@ pub const clock_config = clocks.GlobalConfiguration.init(.{ }); pub fn init() void { + // Reset all peripherals to put system into a known state, - except + // for QSPI pads and the XIP IO bank, as this is fatal if running from + // flash - and the PLLs, as this is fatal if clock muxing has not been + // reset on this boot - and USB, syscfg, as this disturbs USB-to-SWD + // on core 1 + resets.reset_block(resets.masks.init); + + // Remove reset from peripherals which are clocked only by clk_sys and + // clk_ref. Other peripherals stay in reset until we've configured + // clocks. + resets.unreset_block_wait(resets.masks.clocked_by_sys_and_ref); + clock_config.apply(); + + // Peripheral clocks should now all be running + resets.unreset_block_wait(resets.masks.all); } pub fn get_cpu_id() u32 { diff --git a/src/hal/adc.zig b/src/hal/adc.zig index ba293b0..2f6b96b 100644 --- a/src/hal/adc.zig +++ b/src/hal/adc.zig @@ -43,9 +43,9 @@ pub const Input = enum(u3) { switch (input) { .temperature_sensor => set_temp_sensor_enabled(true), else => { - const gpio_num = @as(u32, @enumToInt(input)) + 26; + const pin = gpio.num(@as(u5, @enumToInt(input)) + 26); + pin.set_function(.null); - gpio.set_function(gpio_num, .null); // TODO: implement these, otherwise adc isn't going to work. //gpio.disablePulls(gpio_num); //gpio.setInputEnabled(gpio_num, false); @@ -105,7 +105,6 @@ pub const InputMask = InputMask: { /// Initialize ADC hardware pub fn init() void { - resets.reset(&.{.adc}); ADC.CS.write(.{ .EN = 1, .TS_EN = 0, diff --git a/src/hal/dma.zig b/src/hal/dma.zig new file mode 100644 index 0000000..248e333 --- /dev/null +++ b/src/hal/dma.zig @@ -0,0 +1,131 @@ +const std = @import("std"); +const assert = std.debug.assert; + +const microzig = @import("microzig"); +const chip = microzig.chip; +const DMA = chip.peripherals.DMA; + +const hw = @import("hw.zig"); + +var claimed_channels: u12 = 0; + +pub const Dreq = enum(u6) { + uart0_tx = 20, + uart1_tx = 21, + _, +}; + +pub fn num(n: u4) Channel { + assert(n < 12); + + return @intToEnum(Channel, n); +} + +pub fn claim_unused_channel() ?Channel {} + +pub const Channel = enum(u4) { + _, + + /// panics if the channel is already claimed + pub fn claim(channel: Channel) void { + _ = channel; + @panic("TODO"); + } + + pub fn unclaim(channel: Channel) void { + _ = channel; + @panic("TODO"); + } + + pub fn is_claimed(channel: Channel) bool { + _ = channel; + @panic("TODO"); + } + + const Regs = extern struct { + read_addr: u32, + write_addr: u32, + trans_count: u32, + ctrl_trig: @TypeOf(DMA.CH0_CTRL_TRIG), + + // alias 1 + al1_ctrl: u32, + al1_read_addr: u32, + al1_write_addr: u32, + al1_trans_count: u32, + + // alias 2 + al2_ctrl: u32, + al2_read_addr: u32, + al2_write_addr: u32, + al2_trans_count: u32, + + // alias 3 + al3_ctrl: u32, + al3_read_addr: u32, + al3_write_addr: u32, + al3_trans_count: u32, + }; + + fn get_regs(channel: Channel) *volatile Regs { + const regs = @ptrCast(*volatile [12]Regs, &DMA.CH0_READ_ADDR); + return ®s[@enumToInt(channel)]; + } + + pub const TransferConfig = struct { + transfer_size_bytes: u3, + enable: bool, + read_increment: bool, + write_increment: bool, + dreq: Dreq, + + // TODO: + // chain to + // ring + // byte swapping + }; + + pub fn trigger_transfer( + channel: Channel, + write_addr: u32, + read_addr: u32, + count: u32, + config: TransferConfig, + ) void { + const regs = channel.get_regs(); + regs.read_addr = read_addr; + regs.write_addr = write_addr; + regs.trans_count = count; + regs.ctrl_trig.modify(.{ + .EN = @boolToInt(config.enable), + .DATA_SIZE = .{ + .value = .SIZE_BYTE, + }, + .INCR_READ = @boolToInt(config.read_increment), + .INCR_WRITE = @boolToInt(config.write_increment), + .TREQ_SEL = .{ + .raw = @enumToInt(config.dreq), + }, + }); + } + + pub fn set_irq0_enabled(channel: Channel, enabled: bool) void { + if (enabled) { + const inte0_set = hw.set_alias_raw(&DMA.INTE0); + inte0_set.* = @as(u32, 1) << @enumToInt(channel); + } else { + const inte0_clear = hw.clear_alias_raw(&DMA.INTE0); + inte0_clear.* = @as(u32, 1) << @enumToInt(channel); + } + } + + pub fn acknowledge_irq0(channel: Channel) void { + const ints0_set = hw.set_alias_raw(&DMA.INTS0); + ints0_set.* = @as(u32, 1) << @enumToInt(channel); + } + + pub fn is_busy(channel: Channel) bool { + const regs = channel.get_regs(); + return regs.ctrl_trig.read().BUSY == 1; + } +}; diff --git a/src/hal/gpio.zig b/src/hal/gpio.zig index c0b6bae..02f421e 100644 --- a/src/hal/gpio.zig +++ b/src/hal/gpio.zig @@ -63,92 +63,147 @@ pub const Enabled = enum { enabled, }; -pub inline fn reset() void { - resets.reset(&.{ .io_bank0, .pads_bank0 }); -} +pub const PullUpDown = enum { + up, + down, +}; + +pub fn num(n: u5) Pin { + if (n > 29) + @panic("the RP2040 only has GPIO 0-29"); -/// Initialize a GPIO, set func to SIO -pub inline fn init(comptime gpio: u32) void { - const mask = 1 << gpio; - SIO.GPIO_OE_CLR.raw = mask; - SIO.GPIO_OUT_CLR.raw = mask; - set_function(gpio, .sio); + return @intToEnum(Pin, n); } -/// Reset GPIO back to null function (disables it) -pub inline fn deinit(comptime gpio: u32) void { - set_function(gpio, .null); +pub fn mask(m: u32) Mask { + _ = m; + @panic("TODO"); } -pub const PullUpDown = enum { - up, - down, +pub const Mask = enum(u30) { + _, }; -pub inline fn set_pull(comptime gpio: u32, mode: ?PullUpDown) void { - const gpio_name = comptime std.fmt.comptimePrint("GPIO{d}", .{gpio}); - const gpio_regs = &@field(PADS_BANK0, gpio_name); +pub const Pin = enum(u5) { + _, + + pub const Regs = struct { + status: @TypeOf(IO_BANK0.GPIO0_STATUS), + ctrl: microzig.mmio.Mmio(packed struct(u32) { + FUNCSEL: packed union { + raw: u5, + value: Function, + }, + reserved8: u3, + OUTOVER: packed union { + raw: u2, + value: Override, + }, + reserved12: u2, + OEOVER: packed union { + raw: u2, + value: Override, + }, + reserved16: u2, + INOVER: packed union { + raw: u2, + value: Override, + }, + reserved28: u10, + IRQOVER: packed union { + raw: u2, + value: Override, + }, + padding: u2, + }), + }; + + pub const PadsReg = @TypeOf(PADS_BANK0.GPIO0); + + fn get_regs(gpio: Pin) *volatile Regs { + const regs = @ptrCast(*volatile [30]Regs, &IO_BANK0.GPIO0_STATUS); + return ®s[@enumToInt(gpio)]; + } - if (mode == null) { - gpio_regs.modify(.{ .PUE = 0, .PDE = 0 }); - } else switch (mode.?) { - .up => gpio_regs.modify(.{ .PUE = 1, .PDE = 0 }), - .down => gpio_regs.modify(.{ .PUE = 0, .PDE = 1 }), + fn get_pads_reg(gpio: Pin) *volatile PadsReg { + const regs = @ptrCast(*volatile [30]PadsReg, &PADS_BANK0.GPIO0); + return ®s[@enumToInt(gpio)]; } -} -pub inline fn set_direction(comptime gpio: u32, direction: Direction) void { - const mask = 1 << gpio; - switch (direction) { - .in => SIO.GPIO_OE_CLR.raw = mask, - .out => SIO.GPIO_OE_SET.raw = mask, + pub fn mask(gpio: Pin) u32 { + return @as(u32, 1) << @enumToInt(gpio); } -} -/// Drive a single GPIO high/low -pub inline fn put(comptime gpio: u32, value: u1) void { - std.log.debug("GPIO{} put: {}", .{ gpio, value }); - const mask = 1 << gpio; - switch (value) { - 0 => SIO.GPIO_OUT_CLR.raw = mask, - 1 => SIO.GPIO_OUT_SET.raw = mask, + pub inline fn set_pull(gpio: Pin, mode: ?PullUpDown) void { + const pads_reg = gpio.get_pads_reg(); + + if (mode == null) { + pads_reg.modify(.{ .PUE = 0, .PDE = 0 }); + } else switch (mode.?) { + .up => pads_reg.modify(.{ .PUE = 1, .PDE = 0 }), + .down => pads_reg.modify(.{ .PUE = 0, .PDE = 1 }), + } } -} -pub inline fn toggle(comptime gpio: u32) void { - SIO.GPIO_OUT_XOR.raw = (1 << gpio); -} + pub inline fn set_direction(gpio: Pin, direction: Direction) void { + switch (direction) { + .in => SIO.GPIO_OE_CLR.raw = gpio.mask(), + .out => SIO.GPIO_OE_SET.raw = gpio.mask(), + } + } -pub inline fn read(comptime gpio: u32) u1 { - const mask = 1 << gpio; - return if ((SIO.GPIO_IN.raw & mask) != 0) - 1 - else - 0; -} + /// Drive a single GPIO high/low + pub inline fn put(gpio: Pin, value: u1) void { + switch (value) { + 0 => SIO.GPIO_OUT_CLR.raw = gpio.mask(), + 1 => SIO.GPIO_OUT_SET.raw = gpio.mask(), + } + } -pub inline fn set_function(comptime gpio: u32, function: Function) void { - const pad_bank_reg = comptime std.fmt.comptimePrint("GPIO{}", .{gpio}); - @field(PADS_BANK0, pad_bank_reg).modify(.{ - .IE = 1, - .OD = 0, - }); - - const io_bank_reg = comptime std.fmt.comptimePrint("GPIO{}_CTRL", .{gpio}); - @field(IO_BANK0, io_bank_reg).write(.{ - .FUNCSEL = .{ .raw = @enumToInt(function) }, - .OUTOVER = .{ .value = .NORMAL }, - .INOVER = .{ .value = .NORMAL }, - .IRQOVER = .{ .value = .NORMAL }, - .OEOVER = .{ .value = .NORMAL }, - - .reserved8 = 0, - .reserved12 = 0, - .reserved16 = 0, - .reserved28 = 0, - .padding = 0, - }); -} + pub inline fn toggle(gpio: Pin) void { + SIO.GPIO_OUT_XOR.raw = gpio.mask(); + } + + pub inline fn read(gpio: Pin) u1 { + return if ((SIO.GPIO_IN.raw & gpio.mask()) != 0) + 1 + else + 0; + } + + pub inline fn set_function(gpio: Pin, function: Function) void { + const pads_reg = gpio.get_pads_reg(); + pads_reg.modify(.{ + .IE = 1, + .OD = 0, + }); + + const regs = gpio.get_regs(); + regs.ctrl.modify(.{ + .FUNCSEL = .{ .value = function }, + .OUTOVER = .{ .value = .normal }, + .INOVER = .{ .value = .normal }, + .IRQOVER = .{ .value = .normal }, + .OEOVER = .{ .value = .normal }, + + .reserved8 = 0, + .reserved12 = 0, + .reserved16 = 0, + .reserved28 = 0, + .padding = 0, + }); + } + + //pub fn set_drive_strength(gpio: Gpio, drive: DriveStrength) void { + // _ = drive; + // const pads_reg = gpio.get_pads_reg(); + // pads_reg.modify(.{ + // .DRIVE = .{ + // .value = .@"12mA", + // }, + // }); + //} +}; // setting both uplls enables a "bus keep" function, a weak pull to whatever // is current high/low state of GPIO @@ -165,7 +220,6 @@ pub inline fn set_function(comptime gpio: u32, function: Function) void { //pub fn setInputEnabled(gpio: u32, enabled: Enabled) void {} //pub fn setinputHysteresisEnabled(gpio: u32, enabled: Enabled) void {} //pub fn setSlewRate(gpio: u32, slew_rate: SlewRate) void {} -//pub fn setDriveStrength(gpio: u32, drive: DriveStrength) void {} + //pub fn setIrqEnabled(gpio: u32, events: IrqEvents) void {} //pub fn acknowledgeIrq(gpio: u32, events: IrqEvents) void {} - diff --git a/src/hal/hw.zig b/src/hal/hw.zig index a44aff1..1017c8a 100644 --- a/src/hal/hw.zig +++ b/src/hal/hw.zig @@ -1,11 +1,44 @@ +const std = @import("std"); +const assert = std.debug.assert; + pub const Lock = struct { impl: u32, pub fn claim() Lock { - + @panic("TODO"); } pub fn unlock(lock: Lock) void { - + _ = lock; + @panic("TODO"); } }; + +const rw_bits = @as(u32, 0x0) << 12; +const xor_bits = @as(u32, 0x1) << 12; +const set_bits = @as(u32, 0x2) << 12; +const clear_bits = @as(u32, 0x3) << 12; + +pub fn clear_alias_raw(ptr: anytype) *u32 { + return @intToPtr(*u32, @ptrToInt(ptr) | clear_bits); +} + +pub fn set_alias_raw(ptr: anytype) *u32 { + return @intToPtr(*u32, @ptrToInt(ptr) | set_bits); +} + +pub fn xor_alias_raw(ptr: anytype) *u32 { + return @intToPtr(*u32, @ptrToInt(ptr) | xor_bits); +} + +pub fn clear_alias(ptr: anytype) @TypeOf(ptr) { + return @intToPtr(@TypeOf(ptr), @ptrToInt(ptr) | clear_bits); +} + +pub fn set_alias(ptr: anytype) @TypeOf(ptr) { + return @intToPtr(@TypeOf(ptr), @ptrToInt(ptr) | set_bits); +} + +pub fn xor_alias(ptr: anytype) @TypeOf(ptr) { + return @intToPtr(@TypeOf(ptr), @ptrToInt(ptr) | xor_bits); +} diff --git a/src/hal/pins.zig b/src/hal/pins.zig index 3ff9246..a882df5 100644 --- a/src/hal/pins.zig +++ b/src/hal/pins.zig @@ -315,24 +315,24 @@ const function_table = [@typeInfo(Function).Enum.fields.len][30]u1{ pub fn GPIO(comptime num: u5, comptime direction: gpio.Direction) type { return switch (direction) { .in => struct { - const gpio_num = num; + const pin = gpio.num(num); pub inline fn read(self: @This()) u1 { _ = self; - return gpio.read(gpio_num); + return pin.read(); } }, .out => struct { - const gpio_num = num; + const pin = gpio.num(num); pub inline fn put(self: @This(), value: u1) void { _ = self; - gpio.put(gpio_num, value); + pin.put(value); } pub inline fn toggle(self: @This()) void { _ = self; - gpio.toggle(gpio_num); + pin.toggle(); } }, }; @@ -473,7 +473,6 @@ pub const GlobalConfiguration = struct { // TODO: ensure only one instance of an input function exists const used_gpios = comptime input_gpios | output_gpios; - gpio.reset(); if (used_gpios != 0) { SIO.GPIO_OE_CLR.raw = used_gpios; @@ -482,7 +481,7 @@ pub const GlobalConfiguration = struct { inline for (@typeInfo(GlobalConfiguration).Struct.fields) |field| { if (@field(config, field.name)) |pin_config| { - const gpio_num = @enumToInt(@field(Pin, field.name)); + const pin = gpio.num(@enumToInt(@field(Pin, field.name))); const func = pin_config.function; // xip = 0, @@ -496,17 +495,17 @@ pub const GlobalConfiguration = struct { // @"null" = 0x1f, if (func == .SIO) { - gpio.set_function(gpio_num, .sio); + pin.set_function(.sio); } else if (comptime func.is_pwm()) { - gpio.set_function(gpio_num, .pwm); + pin.set_function(.pwm); } else if (comptime func.is_adc()) { - gpio.set_function(gpio_num, .null); + pin.set_function(.null); } else if (comptime func.isUartTx() or func.isUartRx()) { - gpio.set_function(gpio_num, .uart); + pin.set_function(.uart); } else { @compileError(std.fmt.comptimePrint("Unimplemented pin function. Please implement setting pin function {s} for GPIO {}", .{ @tagName(func), - gpio_num, + @enumToInt(pin), })); } } @@ -527,10 +526,6 @@ pub const GlobalConfiguration = struct { }; } - if (has_pwm) { - resets.reset(&.{.pwm}); - } - if (has_adc) { adc.init(); } diff --git a/src/hal/pio.zig b/src/hal/pio.zig index 22dc5a3..2eb1709 100644 --- a/src/hal/pio.zig +++ b/src/hal/pio.zig @@ -8,6 +8,8 @@ const PIO0 = microzig.chip.peripherals.PIO0; const PIO1 = microzig.chip.peripherals.PIO1; const gpio = @import("gpio.zig"); +const resets = @import("resets.zig"); +const hw = @import("hw.zig"); const assembler = @import("pio/assembler.zig"); const encoder = @import("pio/assembler/encoder.zig"); @@ -29,6 +31,19 @@ pub const StateMachine = enum(u2) { sm1, sm2, sm3, + + pub const Regs = extern struct { + clkdiv: @TypeOf(PIO0.SM0_CLKDIV), + execctrl: @TypeOf(PIO0.SM0_EXECCTRL), + shiftctrl: @TypeOf(PIO0.SM0_SHIFTCTRL), + addr: @TypeOf(PIO0.SM0_ADDR), + instr: @TypeOf(PIO0.SM0_INSTR), + pinctrl: @TypeOf(PIO0.SM0_PINCTRL), + }; + + comptime { + assert(@sizeOf([2]Regs) == (4 * 6 * 2)); + } }; pub const Irq = enum { @@ -41,6 +56,10 @@ pub const Irq = enum { status: @TypeOf(PIO0.IRQ0_INTS), }; + comptime { + assert(@sizeOf([2]Regs) == (3 * 4 * 2)); + } + pub const Source = enum { rx_not_empty, tx_not_full, @@ -50,18 +69,9 @@ pub const Irq = enum { }; }; -pub const StateMachineRegs = extern struct { - clkdiv: @TypeOf(PIO0.SM0_CLKDIV), - execctrl: @TypeOf(PIO0.SM0_EXECCTRL), - shiftctrl: @TypeOf(PIO0.SM0_SHIFTCTRL), - addr: @TypeOf(PIO0.SM0_ADDR), - instr: @TypeOf(PIO0.SM0_INSTR), - pinctrl: @TypeOf(PIO0.SM0_PINCTRL), -}; - pub const ClkDivOptions = struct { - int: u16, - frac: u8, + int: u16 = 1, + frac: u8 = 0, pub fn from_float(div: f32) ClkDivOptions { const fixed = @floatToInt(u24, div * 256); @@ -73,18 +83,20 @@ pub const ClkDivOptions = struct { }; pub const ExecOptions = struct { - wrap: u5, - wrap_target: u5, - side_pindir: bool, - side_set_optional: bool, + wrap: u5 = 31, + wrap_target: u5 = 0, + side_pindir: bool = false, + side_set_optional: bool = false, }; pub const ShiftOptions = struct { autopush: bool = false, autopull: bool = false, - in_shiftdir: Direction = .left, - out_shiftdir: Direction = .left, + in_shiftdir: Direction = .right, + out_shiftdir: Direction = .right, + /// 0 means full 32-bits push_threshold: u5 = 0, + /// 0 means full 32-bits pull_threshold: u5 = 0, join_tx: bool = false, join_rx: bool = false, @@ -104,16 +116,16 @@ pub fn PinMapping(comptime Count: type) type { pub const PinMappingOptions = struct { out: PinMapping(u6) = .{}, - set: PinMapping(u3) = .{}, + set: PinMapping(u3) = .{ .count = 5 }, side_set: PinMapping(u3) = .{}, in_base: u5 = 0, }; pub const StateMachineInitOptions = struct { - clkdiv: ClkDivOptions, - exec: ExecOptions, - shift: ShiftOptions = .{}, + clkdiv: ClkDivOptions = .{}, pin_mappings: PinMappingOptions = .{}, + exec: ExecOptions = .{}, + shift: ShiftOptions = .{}, }; pub const LoadAndStartProgramOptions = struct { @@ -126,6 +138,13 @@ pub const Pio = enum(u1) { pio0 = 0, pio1 = 1, + pub fn reset(self: Pio) void { + switch (self) { + .pio0 => resets.reset(&.{.pio0}), + .pio1 => resets.reset(&.{.pio1}), + } + } + fn get_regs(self: Pio) *volatile PIO { return switch (self) { .pio0 => PIO0, @@ -138,8 +157,8 @@ pub const Pio = enum(u1) { return @ptrCast(*volatile [32]u32, ®s.INSTR_MEM0); } - pub fn gpio_init(self: Pio, comptime pin: u5) void { - gpio.set_function(pin, switch (self) { + pub fn gpio_init(self: Pio, pin: gpio.Pin) void { + pin.set_function(switch (self) { .pio0 => .pio0, .pio1 => .pio1, }); @@ -207,25 +226,19 @@ pub const Pio = enum(u1) { } else error.NoSpace; } - fn get_sm_regs(self: Pio, sm: StateMachine) *volatile StateMachineRegs { + fn get_sm_regs(self: Pio, sm: StateMachine) *volatile StateMachine.Regs { const pio_regs = self.get_regs(); - return switch (sm) { - .sm0 => @ptrCast(*volatile StateMachineRegs, &pio_regs.SM0_CLKDIV), - .sm1 => @ptrCast(*volatile StateMachineRegs, &pio_regs.SM1_CLKDIV), - .sm2 => @ptrCast(*volatile StateMachineRegs, &pio_regs.SM2_CLKDIV), - .sm3 => @ptrCast(*volatile StateMachineRegs, &pio_regs.SM3_CLKDIV), - }; + const sm_regs = @ptrCast(*volatile [4]StateMachine.Regs, &pio_regs.SM0_CLKDIV); + return &sm_regs[@enumToInt(sm)]; } fn get_irq_regs(self: Pio, irq: Irq) *volatile Irq.Regs { const pio_regs = self.get_regs(); - return switch (irq) { - .irq0 => @ptrCast(*volatile Irq.Regs, &pio_regs.IRQ0_INTE), - .irq1 => @ptrCast(*volatile Irq.Regs, &pio_regs.IRQ1_INTE), - }; + const irq_regs = @ptrCast(*volatile [2]Irq.Regs, &pio_regs.IRQ0_INTE); + return &irq_regs[@enumToInt(irq)]; } - pub inline fn sm_set_clkdiv(self: Pio, sm: StateMachine, options: ClkDivOptions) void { + pub fn sm_set_clkdiv(self: Pio, sm: StateMachine, options: ClkDivOptions) void { if (options.int == 0 and options.frac != 0) @panic("invalid params"); @@ -238,7 +251,7 @@ pub const Pio = enum(u1) { }); } - pub inline fn sm_set_exec_options(self: Pio, sm: StateMachine, options: ExecOptions) void { + pub fn sm_set_exec_options(self: Pio, sm: StateMachine, options: ExecOptions) void { const sm_regs = self.get_sm_regs(sm); sm_regs.execctrl.modify(.{ .WRAP_BOTTOM = options.wrap_target, @@ -257,11 +270,11 @@ pub const Pio = enum(u1) { }); } - pub inline fn sm_set_shift_options(self: Pio, sm: StateMachine, options: ShiftOptions) void { + pub fn sm_set_shift_options(self: Pio, sm: StateMachine, options: ShiftOptions) void { const sm_regs = self.get_sm_regs(sm); sm_regs.shiftctrl.write(.{ .AUTOPUSH = @boolToInt(options.autopush), - .AUTOPULL = @boolToInt(options.autopush), + .AUTOPULL = @boolToInt(options.autopull), .IN_SHIFTDIR = @enumToInt(options.in_shiftdir), .OUT_SHIFTDIR = @enumToInt(options.out_shiftdir), @@ -276,7 +289,7 @@ pub const Pio = enum(u1) { }); } - pub inline fn sm_set_pin_mappings(self: Pio, sm: StateMachine, options: PinMappingOptions) void { + pub fn sm_set_pin_mappings(self: Pio, sm: StateMachine, options: PinMappingOptions) void { const sm_regs = self.get_sm_regs(sm); sm_regs.pinctrl.modify(.{ .OUT_BASE = options.out.base, @@ -292,30 +305,32 @@ pub const Pio = enum(u1) { }); } - pub inline fn sm_is_tx_fifo_full(self: Pio, sm: StateMachine) bool { + pub fn sm_is_tx_fifo_full(self: Pio, sm: StateMachine) bool { const regs = self.get_regs(); const txfull = regs.FSTAT.read().TXFULL; return (txfull & (@as(u4, 1) << @enumToInt(sm))) != 0; } - pub inline fn sm_get_tx_fifo(self: Pio, sm: StateMachine) *volatile u32 { + pub fn sm_get_tx_fifo(self: Pio, sm: StateMachine) *volatile u32 { const regs = self.get_regs(); - return switch (sm) { - .sm0 => ®s.TXF0, - .sm1 => ®s.TXF1, - .sm2 => ®s.TXF2, - .sm3 => ®s.TXF3, - }; + const fifos = @ptrCast(*volatile [4]u32, ®s.TXF0); + return &fifos[@enumToInt(sm)]; } - pub inline fn sm_blocking_write(self: Pio, sm: StateMachine, value: u32) void { - while (self.sm_is_tx_fifo_full(sm)) {} - + /// this function writes to the TX FIFO without checking that it's + /// writable, if it's not then the value is ignored + pub fn sm_write(self: Pio, sm: StateMachine, value: u32) void { const fifo_ptr = self.sm_get_tx_fifo(sm); fifo_ptr.* = value; } - pub inline fn sm_set_enabled(self: Pio, sm: StateMachine, enabled: bool) void { + pub fn sm_blocking_write(self: Pio, sm: StateMachine, value: u32) void { + while (self.sm_is_tx_fifo_full(sm)) {} + + self.sm_write(sm, value); + } + + pub fn sm_set_enabled(self: Pio, sm: StateMachine, enabled: bool) void { const regs = self.get_regs(); var value = regs.CTRL.read(); @@ -327,7 +342,7 @@ pub const Pio = enum(u1) { regs.CTRL.write(value); } - inline fn sm_clear_debug(self: Pio, sm: StateMachine) void { + fn sm_clear_debug(self: Pio, sm: StateMachine) void { const regs = self.get_regs(); const mask: u4 = (@as(u4, 1) << @enumToInt(sm)); @@ -343,10 +358,22 @@ pub const Pio = enum(u1) { /// changing the state of fifos will clear them pub fn sm_clear_fifos(self: Pio, sm: StateMachine) void { const sm_regs = self.get_sm_regs(sm); - var shiftctrl = sm_regs.shiftctrl.read(); - shiftctrl.FJOIN_TX ^= 1; - shiftctrl.FJOIN_RX ^= 1; - sm_regs.shiftctrl.write(shiftctrl); + const xor_shiftctrl = hw.xor_alias(&sm_regs.shiftctrl); + const mask = .{ + .FJOIN_TX = 1, + .FJOIN_RX = 1, + + .AUTOPUSH = 0, + .AUTOPULL = 0, + .IN_SHIFTDIR = 0, + .OUT_SHIFTDIR = 0, + .PUSH_THRESH = 0, + .PULL_THRESH = 0, + .reserved16 = 0, + }; + + xor_shiftctrl.write(mask); + xor_shiftctrl.write(mask); } pub fn sm_fifo_level(self: Pio, sm: StateMachine, fifo: Fifo) u4 { @@ -362,14 +389,14 @@ pub const Pio = enum(u1) { return @truncate(u4, levels >> (@as(u5, 4) * num) + offset); } - inline fn interrupt_bit_pos( + fn interrupt_bit_pos( sm: StateMachine, source: Irq.Source, ) u5 { return (@as(u5, 4) * @enumToInt(source)) + @enumToInt(sm); } - pub inline fn sm_clear_interrupt( + pub fn sm_clear_interrupt( self: Pio, sm: StateMachine, irq: Irq, @@ -378,11 +405,11 @@ pub const Pio = enum(u1) { // TODO: why does the raw interrupt register no have irq1/0? _ = irq; const regs = self.get_regs(); - regs.INTR.raw &= ~(@as(u32, 1) << interrupt_bit_pos(sm, source)); + regs.IRQ.raw |= @as(u32, 1) << interrupt_bit_pos(sm, source); } // TODO: be able to disable an interrupt - pub inline fn sm_enable_interrupt( + pub fn sm_enable_interrupt( self: Pio, sm: StateMachine, irq: Irq, @@ -392,7 +419,7 @@ pub const Pio = enum(u1) { irq_regs.enable.raw |= @as(u32, 1) << interrupt_bit_pos(sm, source); } - pub inline fn sm_restart(self: Pio, sm: StateMachine) void { + pub fn sm_restart(self: Pio, sm: StateMachine) void { const mask: u4 = (@as(u4, 1) << @enumToInt(sm)); const regs = self.get_regs(); regs.CTRL.modify(.{ @@ -400,7 +427,7 @@ pub const Pio = enum(u1) { }); } - pub inline fn sm_clkdiv_restart(self: Pio, sm: StateMachine) void { + pub fn sm_clkdiv_restart(self: Pio, sm: StateMachine) void { const mask: u4 = (@as(u4, 1) << @enumToInt(sm)); const regs = self.get_regs(); regs.CTRL.modify(.{ @@ -416,12 +443,11 @@ pub const Pio = enum(u1) { ) void { // Halt the machine, set some sensible defaults self.sm_set_enabled(sm, false); - self.sm_set_pin_mappings(sm, options.pin_mappings); self.sm_set_clkdiv(sm, options.clkdiv); self.sm_set_exec_options(sm, options.exec); self.sm_set_shift_options(sm, options.shift); + self.sm_set_pin_mappings(sm, options.pin_mappings); - //self.set_config(sm, config); self.sm_clear_fifos(sm); self.sm_clear_debug(sm); @@ -480,7 +506,7 @@ pub const Pio = enum(u1) { offset, .side_pindir = if (program.side_set) |side_set| - side_set.pindirs + side_set.pindir else false, diff --git a/src/hal/pio/assembler.zig b/src/hal/pio/assembler.zig index af4153a..3cde6ee 100644 --- a/src/hal/pio/assembler.zig +++ b/src/hal/pio/assembler.zig @@ -121,12 +121,12 @@ fn format_compile_error(comptime message: []const u8, comptime source: []const u }); } -pub fn assemble(comptime source: []const u8, comptime options: AssembleOptions) !Output { +pub fn assemble(comptime source: []const u8, comptime options: AssembleOptions) Output { var diags: ?Diagnostics = null; return assemble_impl(source, &diags, options) catch |err| if (diags) |d| @compileError(format_compile_error(d.message.slice(), source, d.index)) else - err; + @compileError(err); } test "tokenizer and encoder" { diff --git a/src/hal/pio/assembler/encoder.zig b/src/hal/pio/assembler/encoder.zig index a562575..e0bc74c 100644 --- a/src/hal/pio/assembler/encoder.zig +++ b/src/hal/pio/assembler/encoder.zig @@ -27,7 +27,7 @@ pub fn encode( pub const SideSet = struct { count: u3, optional: bool, - pindirs: bool, + pindir: bool, }; pub const Define = struct { @@ -76,15 +76,20 @@ pub fn Encoder(comptime options: Options) type { wrap: ?u5, pub fn to_exported_program(comptime bounded: BoundedProgram) assembler.Program { + comptime var program_name: [bounded.name.len]u8 = undefined; + std.mem.copy(u8, &program_name, bounded.name); return assembler.Program{ - .name = bounded.name, + .name = &program_name, .defines = blk: { var tmp = std.BoundedArray(assembler.Define, options.max_defines).init(0) catch unreachable; - for (bounded.defines.slice()) |define| + for (bounded.defines.slice()) |define| { + comptime var define_name: [define.name.len]u8 = undefined; + std.mem.copy(u8, &define_name, define.name); tmp.append(.{ - .name = define.name, + .name = &define_name, .value = @intCast(i64, define.value), }) catch unreachable; + } break :blk tmp.slice(); }, @@ -281,7 +286,7 @@ pub fn Encoder(comptime options: Options) type { program.side_set = .{ .count = try self.evaluate(u3, program.*, side_set.count, token.index, diags), .optional = side_set.opt, - .pindirs = side_set.pindirs, + .pindir = side_set.pindir, }; self.consume(1); }, @@ -823,7 +828,7 @@ test "encode.side_set.pindirs" { const program = output.programs.get(0); try expectEqual(@as(?u5, 1), program.side_set.?.count); - try expect(program.side_set.?.pindirs); + try expect(program.side_set.?.pindir); } test "encode.label" { diff --git a/src/hal/pio/assembler/tokenizer.zig b/src/hal/pio/assembler/tokenizer.zig index 62e4c0e..29c596d 100644 --- a/src/hal/pio/assembler/tokenizer.zig +++ b/src/hal/pio/assembler/tokenizer.zig @@ -439,7 +439,7 @@ pub const Tokenizer = struct { .side_set = .{ .count = count, .opt = opt, - .pindirs = pindirs, + .pindir = pindirs, }, }, }; @@ -1129,7 +1129,7 @@ pub const Token = struct { pub const SideSet = struct { count: Value, opt: bool = false, - pindirs: bool = false, + pindir: bool = false, }; pub const LangOpt = struct { @@ -1191,7 +1191,7 @@ fn expect_side_set(expected: Token.SideSet, actual: Token) !void { const side_set = actual.data.side_set; try expect_value(expected.count, side_set.count); try expectEqual(expected.opt, side_set.opt); - try expectEqual(expected.pindirs, side_set.pindirs); + try expectEqual(expected.pindir, side_set.pindir); } fn expect_wrap_target(actual: Token) !void { @@ -1538,7 +1538,7 @@ test "tokenize.directive.side_set.opt" { test "tokenize.directive.side_set.pindirs" { const tokens = try bounded_tokenize(".side_set 1 pindirs"); - try expect_side_set(.{ .count = .{ .integer = 1 }, .pindirs = true }, tokens.get(0)); + try expect_side_set(.{ .count = .{ .integer = 1 }, .pindir = true }, tokens.get(0)); } test "tokenize.directive.wrap_target" { diff --git a/src/hal/pll.zig b/src/hal/pll.zig index 62fd9ec..3757049 100644 --- a/src/hal/pll.zig +++ b/src/hal/pll.zig @@ -19,7 +19,7 @@ pub const Configuration = struct { } }; -pub const PLL = enum { +pub const PLL = enum(u1) { sys, usb, diff --git a/src/hal/resets.zig b/src/hal/resets.zig index 218e6b4..f25d550 100644 --- a/src/hal/resets.zig +++ b/src/hal/resets.zig @@ -3,42 +3,39 @@ const EnumField = std.builtin.Type.EnumField; const microzig = @import("microzig"); const RESETS = microzig.chip.peripherals.RESETS; -const Mask = @TypeOf(RESETS.RESET).underlying_type; - -pub const Module = enum { - adc, - busctrl, - dma, - i2c0, - i2c1, - io_bank0, - io_qspi, - jtag, - pads_bank0, - pads_qspi, - pio0, - pio1, - pll_sys, - pll_usb, - pwm, - rtc, - spi0, - spi1, - syscfg, - sysinfo, - tbman, - timer, - uart0, - uart1, - usbctrl, -}; -pub inline fn reset(comptime modules: []const Module) void { - comptime var mask = std.mem.zeroes(Mask); +const hw = @import("hw.zig"); - inline for (modules) |module| - @field(mask, @tagName(module)) = 1; +pub const Mask = packed struct(u32) { + adc: bool = false, + busctrl: bool = false, + dma: bool = false, + i2c0: bool = false, + i2c1: bool = false, + io_bank0: bool = false, + io_qspi: bool = false, + jtag: bool = false, + pads_bank0: bool = false, + pads_qspi: bool = false, + pio0: bool = false, + pio1: bool = false, + pll_sys: bool = false, + pll_usb: bool = false, + pwm: bool = false, + rtc: bool = false, + spi0: bool = false, + spi1: bool = false, + syscfg: bool = false, + sysinfo: bool = false, + tbman: bool = false, + timer: bool = false, + uart0: bool = false, + uart1: bool = false, + usbctrl: bool = false, + padding: u7 = 0, +}; +pub fn reset(mask: Mask) void { const raw_mask = @bitCast(u32, mask); RESETS.RESET.raw = raw_mask; @@ -46,3 +43,90 @@ pub inline fn reset(comptime modules: []const Module) void { while ((RESETS.RESET_DONE.raw & raw_mask) != raw_mask) {} } + +pub fn reset_block(mask: Mask) void { + hw.set_alias_raw(&RESETS.RESET).* = @bitCast(u32, mask); +} + +pub fn unreset_block(mask: Mask) void { + hw.clear_alias_raw(&RESETS.RESET).* = @bitCast(u32, mask); +} + +pub fn unreset_block_wait(mask: Mask) void { + const raw_mask = @bitCast(u32, mask); + hw.clear_alias_raw(&RESETS.RESET).* = raw_mask; + while (RESETS.RESET_DONE.raw & raw_mask != raw_mask) {} +} + +pub const masks = struct { + pub const init = Mask{ + .adc = true, + .busctrl = true, + .dma = true, + .i2c0 = true, + .i2c1 = true, + .io_bank0 = true, + .jtag = true, + .pads_bank0 = true, + .pio0 = true, + .pio1 = true, + .pwm = true, + .rtc = true, + .spi0 = true, + .spi1 = true, + .sysinfo = true, + .tbman = true, + .timer = true, + .uart0 = true, + .uart1 = true, + }; + + pub const all = Mask{ + .adc = true, + .busctrl = true, + .dma = true, + .i2c0 = true, + .i2c1 = true, + .io_bank0 = true, + .io_qspi = true, + .jtag = true, + .pads_bank0 = true, + .pads_qspi = true, + .pio0 = true, + .pio1 = true, + .pll_sys = true, + .pll_usb = true, + .pwm = true, + .rtc = true, + .spi0 = true, + .spi1 = true, + .syscfg = true, + .sysinfo = true, + .tbman = true, + .timer = true, + .uart0 = true, + .uart1 = true, + .usbctrl = true, + }; + + pub const clocked_by_sys_and_ref = Mask{ + .busctrl = true, + .dma = true, + .i2c0 = true, + .i2c1 = true, + .io_bank0 = true, + .io_qspi = true, + .jtag = true, + .pads_bank0 = true, + .pads_qspi = true, + .pio0 = true, + .pio1 = true, + .pll_sys = true, + .pll_usb = true, + .pwm = true, + .syscfg = true, + .sysinfo = true, + .tbman = true, + .timer = true, + }; +}; diff --git a/src/hal/spi.zig b/src/hal/spi.zig index 002ccc4..7170600 100644 --- a/src/hal/spi.zig +++ b/src/hal/spi.zig @@ -14,40 +14,28 @@ const SpiRegs = microzig.chip.types.peripherals.SPI0; pub const Config = struct { clock_config: clocks.GlobalConfiguration, - tx_pin: ?u32 = 19, - rx_pin: ?u32 = 16, - sck_pin: ?u32 = 18, - csn_pin: ?u32 = 17, + tx_pin: ?gpio.Pin = gpio.num(19), + rx_pin: ?gpio.Pin = gpio.num(16), + sck_pin: ?gpio.Pin = gpio.num(18), + csn_pin: ?gpio.Pin = gpio.num(17), baud_rate: u32 = 1000 * 1000, }; -pub const SPI = enum { - spi0, - spi1, +pub fn num(n: u1) SPI { + return @intToEnum(SPI, n); +} + +pub const SPI = enum(u1) { + _, fn get_regs(spi: SPI) *volatile SpiRegs { - return switch (spi) { - .spi0 => SPI0, - .spi1 => SPI1, + return switch (@enumToInt(spi)) { + 0 => SPI0, + 1 => SPI1, }; } - pub fn reset(spi: SPI) void { - switch (spi) { - .spi0 => resets.reset(&.{.spi0}), - .spi1 => resets.reset(&.{.spi1}), - } - } - - pub fn init(comptime id: u32, comptime config: Config) SPI { - const spi: SPI = switch (id) { - 0 => .spi0, - 1 => .spi1, - else => @compileError("there is only spi0 and spi1"), - }; - - spi.reset(); - + pub fn apply(spi: SPI, comptime config: Config) void { const peri_freq = config.clock_config.peri.?.output_freq; _ = spi.set_baudrate(config.baud_rate, peri_freq); @@ -71,12 +59,10 @@ pub const SPI = enum { .SSE = 1, }); - if (config.tx_pin) |pin| gpio.set_function(pin, .spi); - if (config.rx_pin) |pin| gpio.set_function(pin, .spi); - if (config.sck_pin) |pin| gpio.set_function(pin, .spi); - if (config.csn_pin) |pin| gpio.set_function(pin, .spi); - - return spi; + if (config.tx_pin) |pin| pin.set_function(.spi); + if (config.rx_pin) |pin| pin.set_function(.spi); + if (config.sck_pin) |pin| pin.set_function(.spi); + if (config.csn_pin) |pin| pin.set_function(.spi); } pub inline fn is_writable(spi: SPI) bool { diff --git a/src/hal/uart.zig b/src/hal/uart.zig index f4c72c5..6a08b85 100644 --- a/src/hal/uart.zig +++ b/src/hal/uart.zig @@ -8,6 +8,7 @@ const gpio = @import("gpio.zig"); const clocks = @import("clocks.zig"); const resets = @import("resets.zig"); const time = @import("time.zig"); +const dma = @import("dma.zig"); const assert = std.debug.assert; @@ -33,17 +34,20 @@ pub const Parity = enum { pub const Config = struct { clock_config: clocks.GlobalConfiguration, - tx_pin: ?u32 = null, - rx_pin: ?u32 = null, + tx_pin: ?gpio.Pin = null, + rx_pin: ?gpio.Pin = null, baud_rate: u32, word_bits: WordBits = .eight, stop_bits: StopBits = .one, parity: Parity = .none, }; -pub const UART = enum { - uart0, - uart1, +pub fn num(n: u1) UART { + return @intToEnum(UART, n); +} + +pub const UART = enum(u1) { + _, const WriteError = error{}; const ReadError = error{}; @@ -59,23 +63,15 @@ pub const UART = enum { } fn get_regs(uart: UART) *volatile UartRegs { - return switch (uart) { - .uart0 => UART0, - .uart1 => UART1, + return switch (@enumToInt(uart)) { + 0 => UART0, + 1 => UART1, }; } - pub fn init(comptime id: u32, comptime config: Config) UART { - const uart: UART = switch (id) { - 0 => .uart0, - 1 => .uart1, - else => @compileError("there is only uart0 and uart1"), - }; - + pub fn apply(uart: UART, comptime config: Config) void { assert(config.baud_rate > 0); - uart.reset(); - const uart_regs = uart.get_regs(); const peri_freq = config.clock_config.peri.?.output_freq; uart.set_baudrate(config.baud_rate, peri_freq); @@ -96,10 +92,8 @@ pub const UART = enum { }); // TODO comptime assertions - if (config.tx_pin) |tx_pin| gpio.set_function(tx_pin, .uart); - if (config.rx_pin) |rx_pin| gpio.set_function(rx_pin, .uart); - - return uart; + if (config.tx_pin) |tx_pin| tx_pin.set_function(.uart); + if (config.rx_pin) |rx_pin| rx_pin.set_function(.uart); } pub fn is_readable(uart: UART) bool { @@ -122,6 +116,18 @@ pub const UART = enum { return payload.len; } + pub fn tx_fifo(uart: UART) *volatile u32 { + const regs = uart.get_regs(); + return @ptrCast(*volatile u32, ®s.UARTDR); + } + + pub fn dreq_tx(uart: UART) dma.Dreq { + return switch (@enumToInt(uart)) { + 0 => .uart0_tx, + 1 => .uart1_tx, + }; + } + pub fn read(uart: UART, buffer: []u8) ReadError!usize { const uart_regs = uart.get_regs(); for (buffer) |*byte| { @@ -141,13 +147,6 @@ pub const UART = enum { return uart_regs.UARTDR.read().DATA; } - pub fn reset(uart: UART) void { - switch (uart) { - .uart0 => resets.reset(&.{.uart0}), - .uart1 => resets.reset(&.{.uart1}), - } - } - pub fn set_format( uart: UART, word_bits: WordBits, diff --git a/src/hal/usb.zig b/src/hal/usb.zig index 48538a4..e2147f5 100644 --- a/src/hal/usb.zig +++ b/src/hal/usb.zig @@ -130,7 +130,7 @@ pub const F = struct { // clock. // // PLL_USB out of reset - resets.reset(&.{.pll_usb}); + resets.reset(.{ .pll_usb = true }); // Configure it: // // RFDIV = 1 @@ -154,7 +154,7 @@ pub const F = struct { pub fn usb_init_device(device_config: *usb.DeviceConfiguration) void { // Bring USB out of reset - resets.reset(&.{.usbctrl}); + resets.reset(.{ .usbctrl = true }); // Clear the control portion of DPRAM. This may not be necessary -- the // datasheet is ambiguous -- but the C examples do it, and so do we.