Runs zig fmt, implements a good bunch of I²C functions (#65)

Co-authored-by: Felix "xq" Queißner <xq@random-projects.net>
wch-ch32v003
Felix Queißner 1 year ago committed by GitHub
parent 316e241a88
commit 371d4efde4
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23

2
deps/microzig vendored

@ -1 +1 @@
Subproject commit 95889419155b7ffb1b11055549540096eaa2a6c5
Subproject commit a49fad973077dffd5fa0b392720295ad033f076e

@ -14,7 +14,7 @@ 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);
const flash_target_contents = @ptrFromInt([*]const u8, rp2040.flash.XIP_BASE + flash_target_offset);
pub fn panic(message: []const u8, _: ?*std.builtin.StackTrace, _: ?usize) noreturn {
std.log.err("panic: {s}", .{message});

@ -60,7 +60,7 @@ pub fn main() !void {
var i: usize = 0;
std.log.info("Distribution:", .{});
while (i < 256) : (i += 1) {
std.log.info("{} -> {}, {d:2}%", .{ i, dist[i], @intToFloat(f32, dist[i]) / @intToFloat(f32, counter) });
std.log.info("{} -> {}, {d:2}%", .{ i, dist[i], @floatFromInt(f32, dist[i]) / @floatFromInt(f32, counter) });
}
}
time.sleep_ms(1000);

@ -41,7 +41,7 @@ pub var EP1_OUT_CFG: usb.EndpointConfiguration = .{
.length = @intCast(u8, @sizeOf(usb.EndpointDescriptor)),
.descriptor_type = usb.DescType.Endpoint,
.endpoint_address = usb.Dir.Out.endpoint(1),
.attributes = @enumToInt(usb.TransferType.Bulk),
.attributes = @intFromEnum(usb.TransferType.Bulk),
.max_packet_size = 64,
.interval = 0,
},
@ -58,7 +58,7 @@ pub var EP1_IN_CFG: usb.EndpointConfiguration = .{
.length = @intCast(u8, @sizeOf(usb.EndpointDescriptor)),
.descriptor_type = usb.DescType.Endpoint,
.endpoint_address = usb.Dir.In.endpoint(1),
.attributes = @enumToInt(usb.TransferType.Bulk),
.attributes = @intFromEnum(usb.TransferType.Bulk),
.max_packet_size = 64,
.interval = 0,
},

@ -41,7 +41,7 @@ pub var EP1_OUT_CFG: usb.EndpointConfiguration = .{
.length = @intCast(u8, @sizeOf(usb.EndpointDescriptor)),
.descriptor_type = usb.DescType.Endpoint,
.endpoint_address = usb.Dir.Out.endpoint(1),
.attributes = @enumToInt(usb.TransferType.Interrupt),
.attributes = @intFromEnum(usb.TransferType.Interrupt),
.max_packet_size = 64,
.interval = 0,
},
@ -58,7 +58,7 @@ pub var EP1_IN_CFG: usb.EndpointConfiguration = .{
.length = @intCast(u8, @sizeOf(usb.EndpointDescriptor)),
.descriptor_type = usb.DescType.Endpoint,
.endpoint_address = usb.Dir.In.endpoint(1),
.attributes = @enumToInt(usb.TransferType.Interrupt),
.attributes = @intFromEnum(usb.TransferType.Interrupt),
.max_packet_size = 64,
.interval = 0,
},

@ -38,19 +38,19 @@ const led_pin = gpio.num(23);
pub fn main() void {
pio.gpio_init(led_pin);
sm_set_consecutive_pindirs(pio, sm, @enumToInt(led_pin), 1, true);
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 = @intToFloat(f32, rp2040.clock_config.sys.?.output_freq) /
const div = @floatFromInt(f32, 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 = @enumToInt(led_pin),
.base = @intFromEnum(led_pin),
.count = 1,
},
},
@ -85,7 +85,7 @@ fn sm_set_consecutive_pindirs(_pio: Pio, _sm: StateMachine, pin: u5, count: u3,
.delay_side_set = 0,
.payload = .{
.set = .{
.data = @boolToInt(is_out),
.data = @intFromBool(is_out),
.destination = .pindirs,
},
},

@ -65,9 +65,9 @@ pub const devices = struct {
pub const peripherals = struct {
/// System Control Space
pub const MPU = @intToPtr(*volatile types.peripherals.SCS, 0xd90);
pub const MPU = @ptrFromInt(*volatile types.peripherals.SCS, 0xd90);
/// QSPI flash execute-in-place block
pub const XIP_CTRL = @intToPtr(*volatile types.peripherals.XIP_CTRL, 0x14000000);
pub const XIP_CTRL = @ptrFromInt(*volatile types.peripherals.XIP_CTRL, 0x14000000);
/// DW_apb_ssi has the following features:
/// * APB interface Allows for easy integration into a DesignWare Synthesizable Components for AMBA 2 implementation.
/// * APB3 and APB4 protocol support.
@ -94,27 +94,27 @@ pub const devices = struct {
/// - Interrupt polarity active high interrupt lines.
/// - Serial clock polarity low serial-clock polarity directly after reset.
/// - Serial clock phase capture on first edge of serial-clock directly after reset.
pub const XIP_SSI = @intToPtr(*volatile types.peripherals.XIP_SSI, 0x18000000);
pub const SYSINFO = @intToPtr(*volatile types.peripherals.SYSINFO, 0x40000000);
pub const XIP_SSI = @ptrFromInt(*volatile types.peripherals.XIP_SSI, 0x18000000);
pub const SYSINFO = @ptrFromInt(*volatile types.peripherals.SYSINFO, 0x40000000);
/// Register block for various chip control signals
pub const SYSCFG = @intToPtr(*volatile types.peripherals.SYSCFG, 0x40004000);
pub const CLOCKS = @intToPtr(*volatile types.peripherals.CLOCKS, 0x40008000);
pub const RESETS = @intToPtr(*volatile types.peripherals.RESETS, 0x4000c000);
pub const PSM = @intToPtr(*volatile types.peripherals.PSM, 0x40010000);
pub const IO_BANK0 = @intToPtr(*volatile types.peripherals.IO_BANK0, 0x40014000);
pub const IO_QSPI = @intToPtr(*volatile types.peripherals.IO_QSPI, 0x40018000);
pub const PADS_BANK0 = @intToPtr(*volatile types.peripherals.PADS_BANK0, 0x4001c000);
pub const PADS_QSPI = @intToPtr(*volatile types.peripherals.PADS_QSPI, 0x40020000);
pub const SYSCFG = @ptrFromInt(*volatile types.peripherals.SYSCFG, 0x40004000);
pub const CLOCKS = @ptrFromInt(*volatile types.peripherals.CLOCKS, 0x40008000);
pub const RESETS = @ptrFromInt(*volatile types.peripherals.RESETS, 0x4000c000);
pub const PSM = @ptrFromInt(*volatile types.peripherals.PSM, 0x40010000);
pub const IO_BANK0 = @ptrFromInt(*volatile types.peripherals.IO_BANK0, 0x40014000);
pub const IO_QSPI = @ptrFromInt(*volatile types.peripherals.IO_QSPI, 0x40018000);
pub const PADS_BANK0 = @ptrFromInt(*volatile types.peripherals.PADS_BANK0, 0x4001c000);
pub const PADS_QSPI = @ptrFromInt(*volatile types.peripherals.PADS_QSPI, 0x40020000);
/// Controls the crystal oscillator
pub const XOSC = @intToPtr(*volatile types.peripherals.XOSC, 0x40024000);
pub const PLL_SYS = @intToPtr(*volatile types.peripherals.PLL_SYS, 0x40028000);
pub const PLL_USB = @intToPtr(*volatile types.peripherals.PLL_SYS, 0x4002c000);
pub const XOSC = @ptrFromInt(*volatile types.peripherals.XOSC, 0x40024000);
pub const PLL_SYS = @ptrFromInt(*volatile types.peripherals.PLL_SYS, 0x40028000);
pub const PLL_USB = @ptrFromInt(*volatile types.peripherals.PLL_SYS, 0x4002c000);
/// Register block for busfabric control signals and performance counters
pub const BUSCTRL = @intToPtr(*volatile types.peripherals.BUSCTRL, 0x40030000);
pub const UART0 = @intToPtr(*volatile types.peripherals.UART0, 0x40034000);
pub const UART1 = @intToPtr(*volatile types.peripherals.UART0, 0x40038000);
pub const SPI0 = @intToPtr(*volatile types.peripherals.SPI0, 0x4003c000);
pub const SPI1 = @intToPtr(*volatile types.peripherals.SPI0, 0x40040000);
pub const BUSCTRL = @ptrFromInt(*volatile types.peripherals.BUSCTRL, 0x40030000);
pub const UART0 = @ptrFromInt(*volatile types.peripherals.UART0, 0x40034000);
pub const UART1 = @ptrFromInt(*volatile types.peripherals.UART0, 0x40038000);
pub const SPI0 = @ptrFromInt(*volatile types.peripherals.SPI0, 0x4003c000);
pub const SPI1 = @ptrFromInt(*volatile types.peripherals.SPI0, 0x40040000);
/// DW_apb_i2c address block
/// List of configuration constants for the Synopsys I2C hardware (you may see references to these in I2C register header; these are *fixed* values, set at hardware design time):
/// IC_ULTRA_FAST_MODE ................ 0x0
@ -185,7 +185,7 @@ pub const devices = struct {
/// IC_STOP_DET_IF_MASTER_ACTIVE ...... 0x0
/// IC_DEFAULT_UFM_SPKLEN ............. 0x1
/// IC_TX_BUFFER_DEPTH ................ 16
pub const I2C0 = @intToPtr(*volatile types.peripherals.I2C0, 0x40044000);
pub const I2C0 = @ptrFromInt(*volatile types.peripherals.I2C0, 0x40044000);
/// DW_apb_i2c address block
/// List of configuration constants for the Synopsys I2C hardware (you may see references to these in I2C register header; these are *fixed* values, set at hardware design time):
/// IC_ULTRA_FAST_MODE ................ 0x0
@ -256,11 +256,11 @@ pub const devices = struct {
/// IC_STOP_DET_IF_MASTER_ACTIVE ...... 0x0
/// IC_DEFAULT_UFM_SPKLEN ............. 0x1
/// IC_TX_BUFFER_DEPTH ................ 16
pub const I2C1 = @intToPtr(*volatile types.peripherals.I2C0, 0x40048000);
pub const I2C1 = @ptrFromInt(*volatile types.peripherals.I2C0, 0x40048000);
/// Control and data interface to SAR ADC
pub const ADC = @intToPtr(*volatile types.peripherals.ADC, 0x4004c000);
pub const ADC = @ptrFromInt(*volatile types.peripherals.ADC, 0x4004c000);
/// Simple PWM
pub const PWM = @intToPtr(*volatile types.peripherals.PWM, 0x40050000);
pub const PWM = @ptrFromInt(*volatile types.peripherals.PWM, 0x40050000);
/// Controls time and alarms
/// time is a 64 bit value indicating the time in usec since power-on
/// timeh is the top 32 bits of time & timel is the bottom 32 bits
@ -271,35 +271,35 @@ pub const devices = struct {
/// An alarm can be cancelled before it has finished by clearing the alarm_enable
/// When an alarm fires, the corresponding alarm_irq is set and alarm_running is cleared
/// To clear the interrupt write a 1 to the corresponding alarm_irq
pub const TIMER = @intToPtr(*volatile types.peripherals.TIMER, 0x40054000);
pub const WATCHDOG = @intToPtr(*volatile types.peripherals.WATCHDOG, 0x40058000);
pub const TIMER = @ptrFromInt(*volatile types.peripherals.TIMER, 0x40054000);
pub const WATCHDOG = @ptrFromInt(*volatile types.peripherals.WATCHDOG, 0x40058000);
/// Register block to control RTC
pub const RTC = @intToPtr(*volatile types.peripherals.RTC, 0x4005c000);
pub const ROSC = @intToPtr(*volatile types.peripherals.ROSC, 0x40060000);
pub const RTC = @ptrFromInt(*volatile types.peripherals.RTC, 0x4005c000);
pub const ROSC = @ptrFromInt(*volatile types.peripherals.ROSC, 0x40060000);
/// control and status for on-chip voltage regulator and chip level reset subsystem
pub const VREG_AND_CHIP_RESET = @intToPtr(*volatile types.peripherals.VREG_AND_CHIP_RESET, 0x40064000);
pub const VREG_AND_CHIP_RESET = @ptrFromInt(*volatile types.peripherals.VREG_AND_CHIP_RESET, 0x40064000);
/// Testbench manager. Allows the programmer to know what platform their software is running on.
pub const TBMAN = @intToPtr(*volatile types.peripherals.TBMAN, 0x4006c000);
pub const TBMAN = @ptrFromInt(*volatile types.peripherals.TBMAN, 0x4006c000);
/// DMA with separate read and write masters
pub const DMA = @intToPtr(*volatile types.peripherals.DMA, 0x50000000);
pub const DMA = @ptrFromInt(*volatile types.peripherals.DMA, 0x50000000);
/// DPRAM layout for USB device.
pub const USBCTRL_DPRAM = @intToPtr(*volatile types.peripherals.USBCTRL_DPRAM, 0x50100000);
pub const USBCTRL_DPRAM = @ptrFromInt(*volatile types.peripherals.USBCTRL_DPRAM, 0x50100000);
/// USB FS/LS controller device registers
pub const USBCTRL_REGS = @intToPtr(*volatile types.peripherals.USBCTRL_REGS, 0x50110000);
pub const USBCTRL_REGS = @ptrFromInt(*volatile types.peripherals.USBCTRL_REGS, 0x50110000);
/// Programmable IO block
pub const PIO0 = @intToPtr(*volatile types.peripherals.PIO0, 0x50200000);
pub const PIO0 = @ptrFromInt(*volatile types.peripherals.PIO0, 0x50200000);
/// Programmable IO block
pub const PIO1 = @intToPtr(*volatile types.peripherals.PIO0, 0x50300000);
pub const PIO1 = @ptrFromInt(*volatile types.peripherals.PIO0, 0x50300000);
/// Single-cycle IO block
/// Provides core-local and inter-core hardware for the two processors, with single-cycle access.
pub const SIO = @intToPtr(*volatile types.peripherals.SIO, 0xd0000000);
pub const PPB = @intToPtr(*volatile types.peripherals.PPB, 0xe0000000);
pub const SIO = @ptrFromInt(*volatile types.peripherals.SIO, 0xd0000000);
pub const PPB = @ptrFromInt(*volatile types.peripherals.PPB, 0xe0000000);
/// System Tick Timer
pub const SysTick = @intToPtr(*volatile types.peripherals.SysTick, 0xe000e010);
pub const SysTick = @ptrFromInt(*volatile types.peripherals.SysTick, 0xe000e010);
/// System Control Space
pub const NVIC = @intToPtr(*volatile types.peripherals.NVIC, 0xe000e100);
pub const NVIC = @ptrFromInt(*volatile types.peripherals.NVIC, 0xe000e100);
/// System Control Space
pub const SCB = @intToPtr(*volatile types.peripherals.SCB, 0xe000ed00);
pub const SCB = @ptrFromInt(*volatile types.peripherals.SCB, 0xe000ed00);
};
};
};

@ -16,6 +16,7 @@ pub const rand = @import("hal/random.zig");
pub const resets = @import("hal/resets.zig");
pub const rom = @import("hal/rom.zig");
pub const spi = @import("hal/spi.zig");
pub const i2c = @import("hal/i2c.zig");
pub const time = @import("hal/time.zig");
pub const uart = @import("hal/uart.zig");
pub const usb = @import("hal/usb.zig");

@ -17,12 +17,12 @@ pub const Error = error{
/// temp_sensor is not valid because you can refer to it by name.
pub fn input(n: u2) Input {
return @intToEnum(Input, n);
return @enumFromInt(Input, n);
}
/// Enable the ADC controller.
pub fn set_enabled(enabled: bool) void {
ADC.CS.modify(.{ .EN = @boolToInt(enabled) });
ADC.CS.modify(.{ .EN = @intFromBool(enabled) });
}
const Config = struct {
@ -41,7 +41,7 @@ const Config = struct {
pub fn apply(config: Config) void {
ADC.CS.write(.{
.EN = 0,
.TS_EN = @boolToInt(config.temp_sensor_enabled),
.TS_EN = @intFromBool(config.temp_sensor_enabled),
.START_ONCE = 0,
.START_MANY = 0,
.READY = 0,
@ -78,14 +78,14 @@ pub fn apply(config: Config) void {
/// Select analog input for next conversion.
pub fn select_input(in: Input) void {
ADC.CS.modify(.{ .AINSEL = @enumToInt(in) });
ADC.CS.modify(.{ .AINSEL = @intFromEnum(in) });
}
/// Get the currently selected analog input. 0..3 are GPIO 26..29 respectively,
/// 4 is the temperature sensor.
pub fn get_selected_input() Input {
const cs = ADC.SC.read();
return @intToEnum(Input, cs.AINSEL);
return @enumFromInt(Input, cs.AINSEL);
}
pub const Input = enum(u3) {
@ -98,7 +98,7 @@ pub const Input = enum(u3) {
/// temp_sensor.
pub fn get_gpio_pin(in: Input) gpio.Pin {
return switch (in) {
else => gpio.num(@as(u5, @enumToInt(in)) + 26),
else => gpio.num(@as(u5, @intFromEnum(in)) + 26),
.temp_sensor => @panic("temp_sensor doesn't have a pin"),
};
}
@ -120,13 +120,13 @@ pub const Input = enum(u3) {
/// Set to true to power on the temperature sensor.
pub fn set_temp_sensor_enabled(enable: bool) void {
ADC.CS.modify(.{ .TS_EN = @boolToInt(enable) });
ADC.CS.modify(.{ .TS_EN = @intFromBool(enable) });
}
/// T must be floating point.
pub fn temp_sensor_result_to_celcius(comptime T: type, comptime vref: T, result: u12) T {
// TODO: consider fixed-point
const raw = @intToFloat(T, result);
const raw = @floatFromInt(T, result);
const voltage: T = vref * raw / 0x0fff;
return (27.0 - ((voltage - 0.706) / 0.001721));
}
@ -228,9 +228,9 @@ pub const fifo = struct {
/// Apply ADC FIFO configuration and enable it
pub fn apply(config: fifo.Config) void {
ADC.FCS.write(.{
.DREQ_EN = @boolToInt(config.dreq_enabled),
.DREQ_EN = @intFromBool(config.dreq_enabled),
.THRESH = config.thresh,
.SHIFT = @boolToInt(config.shift),
.SHIFT = @intFromBool(config.shift),
.EN = 1,
.EMPTY = 0,
@ -260,7 +260,7 @@ pub const fifo = struct {
pub fn irq_set_enabled(enable: bool) void {
// TODO: check if this works
ADC.INTE.write(.{
.FIFO = @boolToInt(enable),
.FIFO = @intFromBool(enable),
.padding = 0,
});
}

@ -86,7 +86,7 @@ pub const Generator = enum(u32) {
const generators = @ptrCast(*volatile [@typeInfo(Generator).Enum.fields.len]GeneratorRegs, CLOCKS);
fn get_regs(generator: Generator) *volatile GeneratorRegs {
return &generators[@enumToInt(generator)];
return &generators[@intFromEnum(generator)];
}
pub fn has_glitchless_mux(generator: Generator) bool {
@ -666,7 +666,7 @@ pub fn count_frequency_khz(source: Source, comptime clock_config: GlobalConfigur
CLOCKS.FC0_INTERVAL.raw = 10;
CLOCKS.FC0_MIN_KHZ.raw = 0;
CLOCKS.FC0_MAX_KHZ.raw = std.math.maxInt(u32);
CLOCKS.FC0_SRC.raw = @enumToInt(source);
CLOCKS.FC0_SRC.raw = @intFromEnum(source);
while (CLOCKS.FC0_STATUS.read().DONE != 1) {}

@ -19,7 +19,7 @@ pub const Dreq = enum(u6) {
pub fn channel(n: u4) Channel {
assert(n < num_channels);
return @intToEnum(Channel, n);
return @enumFromInt(Channel, n);
}
pub fn claim_unused_channel() ?Channel {
@ -43,11 +43,11 @@ pub const Channel = enum(u4) {
}
pub fn unclaim(chan: Channel) void {
claimed_channels.set(@enumToInt(chan), false);
claimed_channels.set(@intFromEnum(chan), false);
}
pub fn is_claimed(chan: Channel) bool {
return claimed_channels.get(@enumToInt(chan));
return claimed_channels.get(@intFromEnum(chan));
}
const Regs = extern struct {
@ -77,7 +77,7 @@ pub const Channel = enum(u4) {
fn get_regs(chan: Channel) *volatile Regs {
const regs = @ptrCast(*volatile [12]Regs, &DMA.CH0_READ_ADDR);
return &regs[@enumToInt(chan)];
return &regs[@intFromEnum(chan)];
}
pub const TransferConfig = struct {
@ -105,14 +105,14 @@ pub const Channel = enum(u4) {
regs.write_addr = write_addr;
regs.trans_count = count;
regs.ctrl_trig.modify(.{
.EN = @boolToInt(config.enable),
.EN = @intFromBool(config.enable),
.DATA_SIZE = .{
.value = .SIZE_BYTE,
},
.INCR_READ = @boolToInt(config.read_increment),
.INCR_WRITE = @boolToInt(config.write_increment),
.INCR_READ = @intFromBool(config.read_increment),
.INCR_WRITE = @intFromBool(config.write_increment),
.TREQ_SEL = .{
.raw = @enumToInt(config.dreq),
.raw = @intFromEnum(config.dreq),
},
});
}
@ -120,16 +120,16 @@ pub const Channel = enum(u4) {
pub fn set_irq0_enabled(chan: Channel, enabled: bool) void {
if (enabled) {
const inte0_set = hw.set_alias_raw(&DMA.INTE0);
inte0_set.* = @as(u32, 1) << @enumToInt(chan);
inte0_set.* = @as(u32, 1) << @intFromEnum(chan);
} else {
const inte0_clear = hw.clear_alias_raw(&DMA.INTE0);
inte0_clear.* = @as(u32, 1) << @enumToInt(chan);
inte0_clear.* = @as(u32, 1) << @intFromEnum(chan);
}
}
pub fn acknowledge_irq0(chan: Channel) void {
const ints0_set = hw.set_alias_raw(&DMA.INTS0);
ints0_set.* = @as(u32, 1) << @enumToInt(chan);
ints0_set.* = @as(u32, 1) << @intFromEnum(chan);
}
pub fn is_busy(chan: Channel) bool {

@ -23,7 +23,7 @@ pub const boot2 = struct {
/// Copy the 2nd stage bootloader into memory
pub fn flash_init() linksection(".time_critical") void {
if (copyout_valid) return;
const bootloader = @intToPtr([*]u32, XIP_BASE);
const bootloader = @ptrFromInt([*]u32, XIP_BASE);
var i: usize = 0;
while (i < BOOT2_SIZE_BYTES) : (i += 1) {
copyout[i] = bootloader[i];
@ -55,7 +55,7 @@ pub fn range_erase(offset: u32, count: u32) linksection(".time_critical") void {
rom.connect_internal_flash()();
rom.flash_exit_xip()();
rom.flash_range_erase()(offset, count, BLOCK_SIZE, @enumToInt(Command.block_erase));
rom.flash_range_erase()(offset, count, BLOCK_SIZE, @intFromEnum(Command.block_erase));
rom.flash_flush_cache()();
boot2.flash_enable_xip();

@ -72,18 +72,18 @@ pub fn num(n: u5) Pin {
if (n > 29)
@panic("the RP2040 only has GPIO 0-29");
return @intToEnum(Pin, n);
return @enumFromInt(Pin, n);
}
pub fn mask(m: u32) Mask {
return @intToEnum(Mask, m);
return @enumFromInt(Mask, m);
}
pub const Mask = enum(u30) {
_,
pub fn set_function(self: Mask, function: Function) void {
const raw_mask = @enumToInt(self);
const raw_mask = @intFromEnum(self);
for (0..@bitSizeOf(Mask)) |i| {
const bit = @intCast(u5, i);
if (0 != raw_mask & (@as(u32, 1) << bit))
@ -92,7 +92,7 @@ pub const Mask = enum(u30) {
}
pub fn set_direction(self: Mask, direction: Direction) void {
const raw_mask = @enumToInt(self);
const raw_mask = @intFromEnum(self);
switch (direction) {
.out => SIO.GPIO_OE_SET.raw = raw_mask,
.in => SIO.GPIO_OE_CLR.raw = raw_mask,
@ -100,7 +100,7 @@ pub const Mask = enum(u30) {
}
pub fn set_pull(self: Mask, pull: ?Pull) void {
const raw_mask = @enumToInt(self);
const raw_mask = @intFromEnum(self);
for (0..@bitSizeOf(Mask)) |i| {
const bit = @intCast(u5, i);
if (0 != raw_mask & (@as(u32, 1) << bit))
@ -109,11 +109,11 @@ pub const Mask = enum(u30) {
}
pub fn put(self: Mask, value: u32) void {
SIO.GPIO_OUT_XOR.raw = (SIO.GPIO_OUT.raw ^ value) & @enumToInt(self);
SIO.GPIO_OUT_XOR.raw = (SIO.GPIO_OUT.raw ^ value) & @intFromEnum(self);
}
pub fn read(self: Mask) u32 {
return SIO.GPIO_IN.raw & @enumToInt(self);
return SIO.GPIO_IN.raw & @intFromEnum(self);
}
};
@ -155,16 +155,16 @@ pub const Pin = enum(u5) {
fn get_regs(gpio: Pin) *volatile Regs {
const regs = @ptrCast(*volatile [30]Regs, &IO_BANK0.GPIO0_STATUS);
return &regs[@enumToInt(gpio)];
return &regs[@intFromEnum(gpio)];
}
fn get_pads_reg(gpio: Pin) *volatile PadsReg {
const regs = @ptrCast(*volatile [30]PadsReg, &PADS_BANK0.GPIO0);
return &regs[@enumToInt(gpio)];
return &regs[@intFromEnum(gpio)];
}
pub fn mask(gpio: Pin) u32 {
return @as(u32, 1) << @enumToInt(gpio);
return @as(u32, 1) << @intFromEnum(gpio);
}
pub inline fn set_pull(gpio: Pin, pull: ?Pull) void {
@ -206,7 +206,7 @@ pub const Pin = enum(u5) {
pub inline fn set_input_enabled(pin: Pin, enabled: bool) void {
const pads_reg = pin.get_pads_reg();
pads_reg.modify(.{ .IE = @boolToInt(enabled) });
pads_reg.modify(.{ .IE = @intFromBool(enabled) });
}
pub inline fn set_function(gpio: Pin, function: Function) void {

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

@ -0,0 +1,413 @@
const std = @import("std");
const microzig = @import("microzig");
const peripherals = microzig.chip.peripherals;
const I2C0 = peripherals.I2C0;
const I2C1 = peripherals.I2C1;
const gpio = @import("gpio.zig");
const clocks = @import("clocks.zig");
const resets = @import("resets.zig");
const time = @import("time.zig");
const hw = @import("hw.zig");
const I2cRegs = microzig.chip.types.peripherals.I2C0;
pub const Config = struct {
clock_config: clocks.GlobalConfiguration,
sda_pin: ?gpio.Pin = gpio.num(20), // both pins only have I²C as alternate function
scl_pin: ?gpio.Pin = gpio.num(21), // both pins only have I²C as alternate function
baud_rate: u32 = 100_000,
};
pub fn num(n: u1) I2C {
return @enumFromInt(I2C, n);
}
pub const Address = enum(u7) {
_,
pub fn new(addr: u7) Address {
var a = @enumFromInt(Address, addr);
std.debug.assert(!a.is_reserved());
return a;
}
pub fn is_reserved(addr: Address) bool {
return ((@intFromEnum(addr) & 0x78) == 0) or ((@intFromEnum(addr) & 0x78) == 0x78);
}
pub fn format(addr: Address, fmt: []const u8, options: std.fmt.FormatOptions, writer: anytype) !void {
_ = fmt;
_ = options;
try writer.print("I2C(0x{X:0>2}", .{@intFromEnum(addr)});
}
};
pub const I2C = enum(u1) {
_,
fn get_regs(i2c: I2C) *volatile I2cRegs {
return switch (@intFromEnum(i2c)) {
0 => I2C0,
1 => I2C1,
};
}
fn disable(i2c: I2C) void {
i2c.get_regs().IC_ENABLE.write(.{
.ENABLE = .{ .value = .DISABLED },
.ABORT = .{ .value = .DISABLE },
.TX_CMD_BLOCK = .{ .value = .NOT_BLOCKED },
.padding = 0,
});
}
fn enable(i2c: I2C) void {
i2c.get_regs().IC_ENABLE.write(.{
.ENABLE = .{ .value = .ENABLED },
.ABORT = .{ .value = .DISABLE },
.TX_CMD_BLOCK = .{ .value = .NOT_BLOCKED },
.padding = 0,
});
}
/// Initialise the I2C HW block.
pub fn apply(i2c: I2C, comptime config: Config) u32 {
const peri_freq = (comptime config.clock_config.get_frequency(.clk_sys)) orelse @compileError("clk_sys must be set for I²C");
const regs = i2c.get_regs();
i2c.disable();
regs.IC_ENABLE.write(.{
.ENABLE = .{ .value = .DISABLED },
.ABORT = .{ .value = .DISABLE },
.TX_CMD_BLOCK = .{ .value = .NOT_BLOCKED },
.padding = 0,
});
// Configure as a fast-mode master with RepStart support, 7-bit addresses
regs.IC_CON.write(.{
.MASTER_MODE = .{ .value = .ENABLED },
.SPEED = .{ .value = .FAST },
.IC_RESTART_EN = .{ .value = .ENABLED },
.IC_SLAVE_DISABLE = .{ .value = .SLAVE_DISABLED },
.TX_EMPTY_CTRL = .{ .value = .ENABLED },
.IC_10BITADDR_SLAVE = .{ .raw = 0 },
.IC_10BITADDR_MASTER = .{ .raw = 0 },
.STOP_DET_IFADDRESSED = .{ .raw = 0 },
.RX_FIFO_FULL_HLD_CTRL = .{ .raw = 0 },
.STOP_DET_IF_MASTER_ACTIVE = 0,
.padding = 0,
});
// Set FIFO watermarks to 1 to make things simpler. This is encoded by a register value of 0.
regs.IC_RX_TL.write(.{ .RX_TL = 0, .padding = 0 });
regs.IC_TX_TL.write(.{ .TX_TL = 0, .padding = 0 });
// Always enable the DREQ signalling -- harmless if DMA isn't listening
regs.IC_DMA_CR.write(.{
.RDMAE = .{ .value = .ENABLED },
.TDMAE = .{ .value = .ENABLED },
.padding = 0,
});
if (config.sda_pin) |pin| {
pin.set_function(.i2c);
pin.set_pull(.up);
// TODO: Set slew rate
}
if (config.scl_pin) |pin| {
pin.set_function(.i2c);
pin.set_pull(.up);
// TODO: Set slew rate
}
// Re-sets regs.enable upon returning:
return i2c.set_baudrate(config.baud_rate, peri_freq);
}
/// Set I2C baudrate.
pub fn set_baudrate(i2c: I2C, baud_rate: u32, freq_in: u32) u32 {
std.debug.assert(baud_rate != 0);
// I2C is synchronous design that runs from clk_sys
const regs = i2c.get_regs();
// TODO there are some subtleties to I2C timing which we are completely ignoring here
const period: u32 = (freq_in + baud_rate / 2) / baud_rate;
const lcnt: u32 = period * 3 / 5; // oof this one hurts
const hcnt: u32 = period - lcnt;
// Check for out-of-range divisors:
std.debug.assert(hcnt <= std.math.maxInt(u16));
std.debug.assert(lcnt <= std.math.maxInt(u16));
std.debug.assert(hcnt >= 8);
std.debug.assert(lcnt >= 8);
// Per I2C-bus specification a device in standard or fast mode must
// internally provide a hold time of at least 300ns for the SDA signal to
// bridge the undefined region of the falling edge of SCL. A smaller hold
// time of 120ns is used for fast mode plus.
const sda_tx_hold_count: u32 = if (baud_rate < 1_000_000)
// sda_tx_hold_count = freq_in [cycles/s] * 300ns * (1s / 1e9ns)
// Reduce 300/1e9 to 3/1e7 to avoid numbers that don't fit in uint.
// Add 1 to avoid division truncation.
((freq_in * 3) / 10000000) + 1
else
// sda_tx_hold_count = freq_in [cycles/s] * 120ns * (1s / 1e9ns)
// Reduce 120/1e9 to 3/25e6 to avoid numbers that don't fit in uint.
// Add 1 to avoid division truncation.
((freq_in * 3) / 25000000) + 1;
std.debug.assert(sda_tx_hold_count <= lcnt - 2);
i2c.disable();
// Always use "fast" mode (<= 400 kHz, works fine for standard mode too)
regs.IC_CON.modify(.{ .SPEED = .{ .value = .FAST } });
regs.IC_FS_SCL_HCNT.write(.{ .IC_FS_SCL_HCNT = @intCast(u16, hcnt), .padding = 0 });
regs.IC_FS_SCL_LCNT.write(.{ .IC_FS_SCL_LCNT = @intCast(u16, lcnt), .padding = 0 });
regs.IC_FS_SPKLEN.write(.{ .IC_FS_SPKLEN = if (lcnt < 16) 1 else @intCast(u8, lcnt / 16), .padding = 0 });
regs.IC_SDA_HOLD.modify(.{ .IC_SDA_TX_HOLD = @intCast(u16, sda_tx_hold_count) });
i2c.enable();
return freq_in / period;
}
// /// Set I2C port to slave mode.
// pub fn set_slave_mode(i2c: I2C, slave: bool, addr: u8) void {
// //
// }
pub const WriteBlockingUntilError = error{ DeviceNotPresent, NoAcknowledge, Timeout };
/// Attempt to write specified number of bytes to address, blocking until the specified absolute time is reached.
pub fn write_blocking_until(i2c: I2C, addr: Address, src: []const u8, until: time.Absolute) WriteBlockingUntilError!usize {
const Timeout = struct {
limit: time.Absolute,
inline fn perform(tc: @This()) !void {
if (tc.limit.is_reached())
return error.Timeout;
}
};
return i2c.write_blocking_internal(addr, src, Timeout{ .limit = until });
}
pub const ReadBlockingUntilError = error{ DeviceNotPresent, NoAcknowledge, Timeout };
/// Attempt to read specified number of bytes from address, blocking until the specified absolute time is reached.
pub fn read_blocking_until(i2c: I2C, addr: Address, dst: []u8, until: time.Absolute) ReadBlockingUntilError!usize {
const Timeout = struct {
limit: time.Absolute,
inline fn perform(tc: @This()) !void {
if (tc.limit.is_reached())
return error.Timeout;
}
};
return i2c.read_blocking_internal(addr, dst, Timeout{ .limit = until });
}
pub const WriteTimeoutUsError = error{ DeviceNotPresent, NoAcknowledge, Timeout };
/// Attempt to write specified number of bytes to address, with timeout.
pub fn write_timeout_us(i2c: I2C, addr: Address, src: []const u8, timeout: time.Duration) WriteTimeoutUsError!usize {
return i2c.write_blocking_until(addr, src, time.get_time_since_boot().add_duration(timeout));
}
pub const ReadTimeoutUsError = error{ DeviceNotPresent, NoAcknowledge, Timeout };
/// Attempt to read specified number of bytes from address, with timeout.
pub fn read_timeout_us(i2c: I2C, addr: Address, dst: []u8, timeout: time.Duration) ReadTimeoutUsError!usize {
return i2c.read_blocking_until(addr, dst, time.get_time_since_boot().add_duration(timeout));
}
/// Attempt to write specified number of bytes to address, blocking.
pub const WriteBlockingError = error{ DeviceNotPresent, NoAcknowledge, Unexpected };
pub fn write_blocking(i2c: I2C, addr: Address, src: []const u8) WriteBlockingError!usize {
const Timeout = struct {
inline fn perform(tc: @This()) !void {
_ = tc;
}
};
return try i2c.write_blocking_internal(addr, src, Timeout{});
}
/// Attempt to read specified number of bytes from address, blocking.
pub const ReadBlockingError = error{ DeviceNotPresent, NoAcknowledge, Unexpected };
pub fn read_blocking(i2c: I2C, addr: Address, dst: []u8) ReadBlockingError!usize {
const Timeout = struct {
inline fn perform(tc: @This()) !void {
_ = tc;
}
};
try i2c.read_blocking_internal(addr, dst, Timeout{});
}
/// Determine non-blocking write space available.
pub inline fn get_write_available(i2c: I2C) u5 {
return i2c.get_regs().IC_TXFLR.read().TXFLR;
}
/// Determine number of bytes received.
pub inline fn get_read_available(i2c: I2C) u5 {
return i2c.get_regs().IC_RXFLR.read().RXFLR;
}
// /// Write direct to TX FIFO.
// pub fn write_raw_blocking(i2c: I2C, src: []const u8) void {
// //
// }
// /// Read direct from RX FIFO.
// pub fn read_raw_blocking(i2c: I2C, dst: []u8) void {
// //
// }
// /// Pop a byte from I2C Rx FIFO.
// pub fn read_byte_raw(i2c: I2C) u8 {
// //
// }
// /// Push a byte into I2C Tx FIFO.
// pub fn write_byte_raw(i2c: I2C, value: u8) void {
// //
// }
// /// Return the DREQ to use for pacing transfers to/from a particular I2C instance.
// pub fn get_dreq(i2c: I2C, is_tx: bool) u32 {
// //
// }
fn set_address(i2c: I2C, addr: Address) void {
i2c.disable();
i2c.get_regs().IC_TAR.write(.{
.IC_TAR = @intFromEnum(addr),
.GC_OR_START = .{ .value = .GENERAL_CALL },
.SPECIAL = .{ .value = .DISABLED },
.padding = 0,
});
i2c.enable();
}
fn write_blocking_internal(i2c: I2C, addr: Address, src: []const u8, timeout_check: anytype) !usize {
std.debug.assert(!addr.is_reserved());
// Synopsys hw accepts start/stop flags alongside data items in the same
// FIFO word, so no 0 byte transfers.
std.debug.assert(src.len > 0);
const regs = i2c.get_regs();
i2c.set_address(addr);
{
// If the transaction was aborted or if it completed
// successfully wait until the STOP condition has occured.
defer blk: {
// TODO Could there be an abort while waiting for the STOP
// condition here? If so, additional code would be needed here
// to take care of the abort.
while (regs.IC_RAW_INTR_STAT.read().STOP_DET.value == .INACTIVE) {
timeout_check.perform() catch break :blk;
hw.tight_loop_contents();
}
// If there was a timeout, don't attempt to do anything else.
_ = regs.IC_CLR_STOP_DET.read();
}
for (src, 0..) |byte, i| {
const first = (i == 0);
const last = (i == (src.len - 1));
regs.IC_DATA_CMD.write(.{
.RESTART = .{ .raw = @intFromBool(first) }, // TODO: Implement non-restarting variant
.STOP = .{ .raw = @intFromBool(last) }, // TODO: Implement non-restarting variant
.CMD = .{ .value = .WRITE },
.DAT = byte,
.FIRST_DATA_BYTE = .{ .value = .INACTIVE },
.padding = 0,
});
// Wait until the transmission of the address/data from the internal
// shift register has completed. For this to function correctly, the
// TX_EMPTY_CTRL flag in IC_CON must be set. The TX_EMPTY_CTRL flag
// was set in i2c_init.
while (regs.IC_RAW_INTR_STAT.read().TX_EMPTY.value == .INACTIVE) {
try timeout_check.perform();
hw.tight_loop_contents();
}
const abort_reason = regs.IC_TX_ABRT_SOURCE.read();
if (@bitCast(u32, abort_reason) != 0) {
// Note clearing the abort flag also clears the reason, and
// this instance of flag is clear-on-read! Note also the
// IC_CLR_TX_ABRT register always reads as 0.
_ = regs.IC_CLR_TX_ABRT.read();
if (abort_reason.ABRT_7B_ADDR_NOACK.value == .ACTIVE) {
// No reported errors - seems to happen if there is nothing connected to the bus.
// Address byte not acknowledged
return error.DeviceNotPresent;
}
if (abort_reason.ABRT_TXDATA_NOACK.value == .ABRT_TXDATA_NOACK_GENERATED) {
// TODO: How to handle this, also possible to do "return i;" here to signal not everything was transferred
return error.NoAcknowledge;
}
std.log.debug("unexpected i2c abort while writing to {}: {}", .{ addr, abort_reason });
return error.Unexpected;
}
}
}
return src.len;
}
fn read_blocking_internal(i2c: I2C, addr: Address, dst: []u8, timeout_check: anytype) !usize {
std.debug.assert(!addr.is_reserved());
const regs = i2c.get_regs();
i2c.set_address(addr);
for (dst, 0..) |*byte, i| {
const first = (i == 0);
const last = (i == dst.len - 1);
while (i2c.get_write_available(i2c) == 0) {
hw.tight_loop_contents();
}
regs.IC_DATA_CMD.write(.{
.RESTART = .{ .raw = @intFromBool(first) }, // TODO: Implement non-restarting variant
.STOP = .{ .raw = @intFromBool(last) }, // TODO: Implement non-restarting variant
.CMD = .{ .value = .READ },
.DAT = 0,
.FIRST_DATA_BYTE = .{ .value = 0 },
.padding = 0,
});
while (i2c.get_read_available() == 0) {
const abort_reason = regs.IC_TX_ABRT_SOURCE.read();
const abort = (regs.IC_CLR_TX_ABRT.read().CLR_TX_ABRT != 0);
if (abort) {
if (abort_reason.ABRT_7B_ADDR_NOACK.value == .ACTIVE)
return error.DeviceNotPresent;
std.log.debug("unexpected i2c abort while reading from {}: {}", .{ addr, abort_reason });
return error.Unexpected;
}
try timeout_check.perform();
}
byte.* = regs.IC_DATA_CMD.read().DAT;
}
return dst.len;
}
};

@ -70,7 +70,7 @@ pub fn launch_core1_with_stack(entrypoint: *const fn () void, stack: []u32) void
fn wrapper(_: u32, _: u32, _: u32, _: u32, entry: u32, stack_base: [*]u32) callconv(.C) void {
// TODO: protect stack using MPU
_ = stack_base;
@intToPtr(*const fn () void, entry)();
@ptrFromInt(*const fn () void, entry)();
}
}.wrapper;
@ -79,12 +79,12 @@ pub fn launch_core1_with_stack(entrypoint: *const fn () void, stack: []u32) void
while (PSM.FRCE_OFF.read().proc1 != 1) microzig.cpu.nop();
PSM.FRCE_OFF.modify(.{ .proc1 = 0 });
stack[stack.len - 2] = @ptrToInt(entrypoint);
stack[stack.len - 1] = @ptrToInt(stack.ptr);
stack[stack.len - 2] = @intFromPtr(entrypoint);
stack[stack.len - 1] = @intFromPtr(stack.ptr);
// calculate top of the stack
const stack_ptr: u32 =
@ptrToInt(stack.ptr) +
@intFromPtr(stack.ptr) +
(stack.len - 2) * @sizeOf(u32); // pop the two elements we "pushed" above
// after reseting core1 is waiting for this specific sequence
@ -94,7 +94,7 @@ pub fn launch_core1_with_stack(entrypoint: *const fn () void, stack: []u32) void
1,
SCB.VTOR.raw,
stack_ptr,
@ptrToInt(wrapper),
@intFromPtr(wrapper),
};
var seq: usize = 0;

@ -355,7 +355,7 @@ pub fn Pins(comptime config: GlobalConfiguration) type {
if (pin_config.function == .SIO) {
pin_field.name = pin_config.name orelse field.name;
pin_field.type = GPIO(@enumToInt(@field(Pin, field.name)), pin_config.direction orelse .in);
pin_field.type = GPIO(@intFromEnum(@field(Pin, field.name)), pin_config.direction orelse .in);
} else if (pin_config.function.is_pwm()) {
pin_field.name = pin_config.name orelse @tagName(pin_config.function);
pin_field.type = pwm.Pwm(pin_config.function.pwm_slice(), pin_config.function.pwm_channel());
@ -450,8 +450,8 @@ pub const GlobalConfiguration = struct {
comptime {
inline for (@typeInfo(GlobalConfiguration).Struct.fields) |field|
if (@field(config, field.name)) |pin_config| {
const gpio_num = @enumToInt(@field(Pin, field.name));
if (0 == function_table[@enumToInt(pin_config.function)][gpio_num])
const gpio_num = @intFromEnum(@field(Pin, field.name));
if (0 == function_table[@intFromEnum(pin_config.function)][gpio_num])
@compileError(comptimePrint("{s} cannot be configured for {}", .{ field.name, pin_config.function }));
if (pin_config.function == .SIO) {
@ -481,7 +481,7 @@ pub const GlobalConfiguration = struct {
inline for (@typeInfo(GlobalConfiguration).Struct.fields) |field| {
if (@field(config, field.name)) |pin_config| {
const pin = gpio.num(@enumToInt(@field(Pin, field.name)));
const pin = gpio.num(@intFromEnum(@field(Pin, field.name)));
const func = pin_config.function;
// xip = 0,
@ -505,7 +505,7 @@ pub const GlobalConfiguration = struct {
} else {
@compileError(std.fmt.comptimePrint("Unimplemented pin function. Please implement setting pin function {s} for GPIO {}", .{
@tagName(func),
@enumToInt(pin),
@intFromEnum(pin),
}));
}
}
@ -517,7 +517,7 @@ pub const GlobalConfiguration = struct {
if (input_gpios != 0) {
inline for (@typeInfo(GlobalConfiguration).Struct.fields) |field|
if (@field(config, field.name)) |pin_config| {
const gpio_num = @enumToInt(@field(Pin, field.name));
const gpio_num = @intFromEnum(@field(Pin, field.name));
const pull = pin_config.pull orelse continue;
if (comptime pin_config.get_direction() != .in)
@compileError("Only input pins can have pull up/down enabled");

@ -74,7 +74,7 @@ pub const ClkDivOptions = struct {
frac: u8 = 0,
pub fn from_float(div: f32) ClkDivOptions {
const fixed = @floatToInt(u24, div * 256);
const fixed = @intFromFloat(u24, div * 256);
return ClkDivOptions{
.int = @truncate(u16, fixed >> 8),
.frac = @truncate(u8, fixed),
@ -169,7 +169,7 @@ pub const Pio = enum(u1) {
if (origin != offset)
return false;
const used_mask = used_instruction_space[@enumToInt(self)];
const used_mask = used_instruction_space[@intFromEnum(self)];
const program_mask = program.get_mask();
// We can add the program if the masks don't overlap, if there is
@ -199,7 +199,7 @@ pub const Pio = enum(u1) {
instruction_memory[i] = insn;
const program_mask = program.get_mask();
used_instruction_space[@enumToInt(self)] |= program_mask << offset;
used_instruction_space[@intFromEnum(self)] |= program_mask << offset;
}
/// Public functions will need to lock independently, so only exposing this function for now
@ -216,12 +216,12 @@ pub const Pio = enum(u1) {
// TODO: const lock = hw.Lock.claim()
// defer lock.unlock();
const claimed_mask = claimed_state_machines[@enumToInt(self)];
const claimed_mask = claimed_state_machines[@intFromEnum(self)];
return for (0..4) |i| {
const sm_mask = (@as(u4, 1) << @intCast(u2, i));
if (0 == (claimed_mask & sm_mask)) {
claimed_state_machines[@enumToInt(self)] |= sm_mask;
break @intToEnum(StateMachine, i);
claimed_state_machines[@intFromEnum(self)] |= sm_mask;
break @enumFromInt(StateMachine, i);
}
} else error.NoSpace;
}
@ -229,13 +229,13 @@ pub const Pio = enum(u1) {
pub fn get_sm_regs(self: Pio, sm: StateMachine) *volatile StateMachine.Regs {
const pio_regs = self.get_regs();
const sm_regs = @ptrCast(*volatile [4]StateMachine.Regs, &pio_regs.SM0_CLKDIV);
return &sm_regs[@enumToInt(sm)];
return &sm_regs[@intFromEnum(sm)];
}
fn get_irq_regs(self: Pio, irq: Irq) *volatile Irq.Regs {
const pio_regs = self.get_regs();
const irq_regs = @ptrCast(*volatile [2]Irq.Regs, &pio_regs.IRQ0_INTE);
return &irq_regs[@enumToInt(irq)];
return &irq_regs[@intFromEnum(irq)];
}
pub fn sm_set_clkdiv(self: Pio, sm: StateMachine, options: ClkDivOptions) void {
@ -256,8 +256,8 @@ pub const Pio = enum(u1) {
sm_regs.execctrl.modify(.{
.WRAP_BOTTOM = options.wrap_target,
.WRAP_TOP = options.wrap,
.SIDE_PINDIR = @boolToInt(options.side_pindir),
.SIDE_EN = @boolToInt(options.side_set_optional),
.SIDE_PINDIR = @intFromBool(options.side_pindir),
.SIDE_EN = @intFromBool(options.side_set_optional),
// TODO: plug in rest of the options
// STATUS_N
@ -273,17 +273,17 @@ pub const Pio = enum(u1) {
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.autopull),
.AUTOPUSH = @intFromBool(options.autopush),
.AUTOPULL = @intFromBool(options.autopull),
.IN_SHIFTDIR = @enumToInt(options.in_shiftdir),
.OUT_SHIFTDIR = @enumToInt(options.out_shiftdir),
.IN_SHIFTDIR = @intFromEnum(options.in_shiftdir),
.OUT_SHIFTDIR = @intFromEnum(options.out_shiftdir),
.PUSH_THRESH = options.push_threshold,
.PULL_THRESH = options.pull_threshold,
.FJOIN_TX = @boolToInt(options.join_tx),
.FJOIN_RX = @boolToInt(options.join_rx),
.FJOIN_TX = @intFromBool(options.join_tx),
.FJOIN_RX = @intFromBool(options.join_rx),
.reserved16 = 0,
});
@ -308,13 +308,13 @@ pub const Pio = enum(u1) {
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;
return (txfull & (@as(u4, 1) << @intFromEnum(sm))) != 0;
}
pub fn sm_get_tx_fifo(self: Pio, sm: StateMachine) *volatile u32 {
const regs = self.get_regs();
const fifos = @ptrCast(*volatile [4]u32, &regs.TXF0);
return &fifos[@enumToInt(sm)];
return &fifos[@intFromEnum(sm)];
}
/// this function writes to the TX FIFO without checking that it's
@ -335,16 +335,16 @@ pub const Pio = enum(u1) {
var value = regs.CTRL.read();
if (enabled)
value.SM_ENABLE |= @as(u4, 1) << @enumToInt(sm)
value.SM_ENABLE |= @as(u4, 1) << @intFromEnum(sm)
else
value.SM_ENABLE &= ~(@as(u4, 1) << @enumToInt(sm));
value.SM_ENABLE &= ~(@as(u4, 1) << @intFromEnum(sm));
regs.CTRL.write(value);
}
fn sm_clear_debug(self: Pio, sm: StateMachine) void {
const regs = self.get_regs();
const mask: u4 = (@as(u4, 1) << @enumToInt(sm));
const mask: u4 = (@as(u4, 1) << @intFromEnum(sm));
// write 1 to clear this register
regs.FDEBUG.modify(.{
@ -377,7 +377,7 @@ pub const Pio = enum(u1) {
}
pub fn sm_fifo_level(self: Pio, sm: StateMachine, fifo: Fifo) u4 {
const num = @enumToInt(sm);
const num = @intFromEnum(sm);
const offset: u5 = switch (fifo) {
.tx => 0,
.rx => 4,
@ -393,7 +393,7 @@ pub const Pio = enum(u1) {
sm: StateMachine,
source: Irq.Source,
) u5 {
return (@as(u5, 4) * @enumToInt(source)) + @enumToInt(sm);
return (@as(u5, 4) * @intFromEnum(source)) + @intFromEnum(sm);
}
pub fn sm_clear_interrupt(
@ -420,7 +420,7 @@ pub const Pio = enum(u1) {
}
pub fn sm_restart(self: Pio, sm: StateMachine) void {
const mask: u4 = (@as(u4, 1) << @enumToInt(sm));
const mask: u4 = (@as(u4, 1) << @intFromEnum(sm));
const regs = self.get_regs();
regs.CTRL.modify(.{
.SM_RESTART = mask,
@ -428,7 +428,7 @@ pub const Pio = enum(u1) {
}
pub fn sm_clkdiv_restart(self: Pio, sm: StateMachine) void {
const mask: u4 = (@as(u4, 1) << @enumToInt(sm));
const mask: u4 = (@as(u4, 1) << @intFromEnum(sm));
const regs = self.get_regs();
regs.CTRL.modify(.{
.CLKDIV_RESTART = mask,

@ -340,14 +340,14 @@ pub fn Encoder(comptime options: Options) type {
},
.push => |push| .{
.push = .{
.if_full = @boolToInt(push.iffull),
.block = @boolToInt(push.block),
.if_full = @intFromBool(push.iffull),
.block = @intFromBool(push.block),
},
},
.pull => |pull| .{
.pull = .{
.if_empty = @boolToInt(pull.ifempty),
.block = @boolToInt(pull.block),
.if_empty = @intFromBool(pull.ifempty),
.block = @intFromBool(pull.block),
},
},
.mov => |mov| .{
@ -361,8 +361,8 @@ pub fn Encoder(comptime options: Options) type {
const irq_num = try self.evaluate(u5, program.*, irq.num, token_index, diags);
break :blk .{
.irq = .{
.clear = @boolToInt(irq.clear),
.wait = @boolToInt(irq.wait),
.clear = @intFromBool(irq.clear),
.wait = @intFromBool(irq.wait),
.index = if (irq.rel)
@as(u5, 0x10) | irq_num
else

@ -10,7 +10,7 @@ fn get_regs(comptime slice: u32) *volatile Regs {
@import("std").debug.assert(slice < 8);
const PwmType = microzig.chip.types.peripherals.PWM;
const reg_diff = comptime @offsetOf(PwmType, "CH1_CSR") - @offsetOf(PwmType, "CH0_CSR");
return @intToPtr(*volatile Regs, @ptrToInt(PWM) + reg_diff * slice);
return @ptrFromInt(*volatile Regs, @intFromPtr(PWM) + reg_diff * slice);
}
pub fn Pwm(comptime slice_num: u32, comptime chan: Channel) type {
@ -74,7 +74,7 @@ const Regs = extern struct {
pub inline fn set_slice_phase_correct(comptime slice: u32, phase_correct: bool) void {
log.debug("PWM{} set phase correct: {}", .{ slice, phase_correct });
get_regs(slice).csr.modify(.{
.PH_CORRECT = @boolToInt(phase_correct),
.PH_CORRECT = @intFromBool(phase_correct),
});
}
@ -89,7 +89,7 @@ pub inline fn set_slice_clk_div(comptime slice: u32, integer: u8, fraction: u4)
pub inline fn set_slice_clk_div_mode(comptime slice: u32, mode: ClkDivMode) void {
log.debug("PWM{} set clk div mode: {}", .{ slice, mode });
get_regs(slice).csr.modify(.{
.DIVMODE = @enumToInt(mode),
.DIVMODE = @intFromEnum(mode),
});
}
@ -100,10 +100,10 @@ pub inline fn set_channel_inversion(
) void {
switch (channel) {
.a => get_regs(slice).csr.modify(.{
.A_INV = @boolToInt(invert),
.A_INV = @intFromBool(invert),
}),
.b => get_regs(slice).csr.modifi(.{
.B_INV = @boolToInt(invert),
.B_INV = @intFromBool(invert),
}),
}
}

@ -100,8 +100,8 @@ pub fn rom_table_code(c1: u8, c2: u8) u32 {
///
/// The converted pointer
pub inline fn rom_hword_as_ptr(rom_addr: u32) *anyopaque {
const ptr_to_ptr = @intToPtr(*u16, rom_addr);
return @intToPtr(*anyopaque, @intCast(usize, ptr_to_ptr.*));
const ptr_to_ptr = @ptrFromInt(*u16, rom_addr);
return @ptrFromInt(*anyopaque, @intCast(usize, ptr_to_ptr.*));
}
/// Lookup a bootrom function by code (inline)
@ -115,7 +115,7 @@ pub inline fn rom_hword_as_ptr(rom_addr: u32) *anyopaque {
pub inline fn _rom_func_lookup(code: Code) *anyopaque {
const rom_table_lookup = @ptrCast(*signatures.rom_table_lookup, rom_hword_as_ptr(0x18));
const func_table = @ptrCast(*u16, @alignCast(2, rom_hword_as_ptr(0x14)));
return rom_table_lookup(func_table, @enumToInt(code));
return rom_table_lookup(func_table, @intFromEnum(code));
}
/// Lookup a bootrom function by code

@ -22,14 +22,14 @@ pub const Config = struct {
};
pub fn num(n: u1) SPI {
return @intToEnum(SPI, n);
return @enumFromInt(SPI, n);
}
pub const SPI = enum(u1) {
_,
fn get_regs(spi: SPI) *volatile SpiRegs {
return switch (@enumToInt(spi)) {
return switch (@intFromEnum(spi)) {
0 => SPI0,
1 => SPI1,
};

@ -7,11 +7,11 @@ pub const Absolute = enum(u64) {
_,
pub fn from_us(us: u64) Absolute {
return @intToEnum(Absolute, us);
return @enumFromInt(Absolute, us);
}
pub fn to_us(time: Absolute) u64 {
return @enumToInt(time);
return @intFromEnum(time);
}
pub fn is_reached_by(deadline: Absolute, point: Absolute) bool {
@ -36,7 +36,7 @@ pub const Duration = enum(u64) {
_,
pub fn from_us(us: u64) Duration {
return @intToEnum(Duration, us);
return @enumFromInt(Duration, us);
}
pub fn from_ms(ms: u64) Duration {
@ -44,7 +44,7 @@ pub const Duration = enum(u64) {
}
pub fn to_us(duration: Duration) u64 {
return @enumToInt(duration);
return @intFromEnum(duration);
}
pub fn less_than(self: Duration, other: Duration) bool {
@ -67,14 +67,14 @@ pub fn get_time_since_boot() Absolute {
var low_word = TIMER.TIMERAWL;
const next_high_word = TIMER.TIMERAWH;
if (next_high_word == high_word)
break @intToEnum(Absolute, @intCast(u64, high_word) << 32 | low_word);
break @enumFromInt(Absolute, @intCast(u64, high_word) << 32 | low_word);
high_word = next_high_word;
} else unreachable;
}
pub fn make_timeout_us(timeout_us: u64) Absolute {
return @intToEnum(Absolute, get_time_since_boot().to_us() + timeout_us);
return @enumFromInt(Absolute, get_time_since_boot().to_us() + timeout_us);
}
pub fn sleep_ms(time_ms: u32) void {

@ -43,7 +43,7 @@ pub const Config = struct {
};
pub fn num(n: u1) UART {
return @intToEnum(UART, n);
return @enumFromInt(UART, n);
}
pub const UART = enum(u1) {
@ -63,7 +63,7 @@ pub const UART = enum(u1) {
}
fn get_regs(uart: UART) *volatile UartRegs {
return switch (@enumToInt(uart)) {
return switch (@intFromEnum(uart)) {
0 => UART0,
1 => UART1,
};
@ -122,7 +122,7 @@ pub const UART = enum(u1) {
}
pub fn dreq_tx(uart: UART) dma.Dreq {
return switch (@enumToInt(uart)) {
return switch (@intFromEnum(uart)) {
0 => .uart0_tx,
1 => .uart1_tx,
};

@ -45,7 +45,7 @@ pub var EP0_OUT_CFG: usb.EndpointConfiguration = .{
.length = @intCast(u8, @sizeOf(usb.EndpointDescriptor)),
.descriptor_type = usb.DescType.Endpoint,
.endpoint_address = usb.EP0_OUT_ADDR,
.attributes = @enumToInt(usb.TransferType.Control),
.attributes = @intFromEnum(usb.TransferType.Control),
.max_packet_size = 64,
.interval = 0,
},
@ -60,7 +60,7 @@ pub var EP0_IN_CFG: usb.EndpointConfiguration = .{
.length = @intCast(u8, @sizeOf(usb.EndpointDescriptor)),
.descriptor_type = usb.DescType.Endpoint,
.endpoint_address = usb.EP0_IN_ADDR,
.attributes = @enumToInt(usb.TransferType.Control),
.attributes = @intFromEnum(usb.TransferType.Control),
.max_packet_size = 64,
.interval = 0,
},
@ -89,26 +89,26 @@ pub const buffers = struct {
/// Mapping to the different data buffers in DPSRAM
pub var B: usb.Buffers = .{
.ep0_buffer0 = @intToPtr([*]u8, USB_EP0_BUFFER0),
.ep0_buffer1 = @intToPtr([*]u8, USB_EP0_BUFFER1),
.ep0_buffer0 = @ptrFromInt([*]u8, USB_EP0_BUFFER0),
.ep0_buffer1 = @ptrFromInt([*]u8, USB_EP0_BUFFER1),
// We will initialize this comptime in a loop
.rest = .{
@intToPtr([*]u8, USB_BUFFERS + (0 * BUFFER_SIZE)),
@intToPtr([*]u8, USB_BUFFERS + (1 * BUFFER_SIZE)),
@intToPtr([*]u8, USB_BUFFERS + (2 * BUFFER_SIZE)),
@intToPtr([*]u8, USB_BUFFERS + (3 * BUFFER_SIZE)),
@intToPtr([*]u8, USB_BUFFERS + (4 * BUFFER_SIZE)),
@intToPtr([*]u8, USB_BUFFERS + (5 * BUFFER_SIZE)),
@intToPtr([*]u8, USB_BUFFERS + (6 * BUFFER_SIZE)),
@intToPtr([*]u8, USB_BUFFERS + (7 * BUFFER_SIZE)),
@intToPtr([*]u8, USB_BUFFERS + (8 * BUFFER_SIZE)),
@intToPtr([*]u8, USB_BUFFERS + (9 * BUFFER_SIZE)),
@intToPtr([*]u8, USB_BUFFERS + (10 * BUFFER_SIZE)),
@intToPtr([*]u8, USB_BUFFERS + (11 * BUFFER_SIZE)),
@intToPtr([*]u8, USB_BUFFERS + (12 * BUFFER_SIZE)),
@intToPtr([*]u8, USB_BUFFERS + (13 * BUFFER_SIZE)),
@intToPtr([*]u8, USB_BUFFERS + (14 * BUFFER_SIZE)),
@intToPtr([*]u8, USB_BUFFERS + (15 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (0 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (1 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (2 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (3 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (4 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (5 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (6 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (7 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (8 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (9 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (10 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (11 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (12 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (13 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (14 * BUFFER_SIZE)),
@ptrFromInt([*]u8, USB_BUFFERS + (15 * BUFFER_SIZE)),
},
};
};
@ -273,8 +273,8 @@ pub const F = struct {
if (ep.endpoint_control_index) |epci| {
// We need to compute the offset from the base of USB SRAM to the
// buffer we're choosing, because that's how the peripheral do.
const buf_base = @ptrToInt(buffers.B.get(ep.data_buffer_index));
const dpram_base = @ptrToInt(peripherals.USBCTRL_DPRAM);
const buf_base = @intFromPtr(buffers.B.get(ep.data_buffer_index));
const dpram_base = @intFromPtr(peripherals.USBCTRL_DPRAM);
// The offset _should_ fit in a u16, but if we've gotten something
// wrong in the past few lines, a common symptom will be integer
// overflow producing a Very Large Number,

Loading…
Cancel
Save