diff --git a/examples/stmicro/stm32/src/blinky.zig b/examples/stmicro/stm32/src/blinky.zig index c9258c0eb..ffc517867 100644 --- a/examples/stmicro/stm32/src/blinky.zig +++ b/examples/stmicro/stm32/src/blinky.zig @@ -21,26 +21,33 @@ pub fn main() !void { }; break :res .{ pins, all_leds }; } else if (comptime microzig.config.board_name != null and std.mem.eql(u8, microzig.config.board_name.?, "STM32F3DISCOVERY")) { - const pins = (stm32.pins.GlobalConfiguration{ .GPIOE = .{ - .PE8 = .{ .mode = .{ .output = .push_pull } }, - .PE9 = .{ .mode = .{ .output = .push_pull } }, - .PE10 = .{ .mode = .{ .output = .push_pull } }, - .PE11 = .{ .mode = .{ .output = .push_pull } }, - .PE12 = .{ .mode = .{ .output = .push_pull } }, - .PE13 = .{ .mode = .{ .output = .push_pull } }, - .PE14 = .{ .mode = .{ .output = .push_pull } }, - .PE15 = .{ .mode = .{ .output = .push_pull } }, - } }).apply(); + const pins = (stm32.pins.GlobalConfiguration{ + .GPIOC = .{ + .PIN4 = .{ .mode = .{ .alternate_function = .{ .afr = .AF7 } } }, + .PIN5 = .{ .mode = .{ .alternate_function = .{ .afr = .AF7 } } }, + }, + .GPIOE = .{ + .PIN8 = .{ .mode = .{ .output = .{ .resistor = .Floating, .o_type = .PushPull } } }, + .PIN9 = .{ .mode = .{ .output = .{ .resistor = .Floating, .o_type = .PushPull } } }, + .PIN10 = .{ .mode = .{ .output = .{ .resistor = .Floating, .o_type = .PushPull } } }, + .PIN11 = .{ .mode = .{ .output = .{ .resistor = .Floating, .o_type = .PushPull } } }, + .PIN12 = .{ .mode = .{ .output = .{ .resistor = .Floating, .o_type = .PushPull } } }, + .PIN13 = .{ .mode = .{ .output = .{ .resistor = .Floating, .o_type = .PushPull } } }, + .PIN14 = .{ .mode = .{ .output = .{ .resistor = .Floating, .o_type = .PushPull } } }, + .PIN15 = .{ .mode = .{ .output = .{ .resistor = .Floating, .o_type = .PushPull } } }, + }, + }).apply(); const all_leds = .{ - pins.PE8, - pins.PE9, - pins.PE10, - pins.PE11, - pins.PE12, - pins.PE13, - pins.PE14, - pins.PE15, + pins.PIN8, + pins.PIN9, + pins.PIN10, + pins.PIN11, + pins.PIN12, + pins.PIN13, + pins.PIN14, + pins.PIN15, }; + break :res .{ pins, all_leds }; } else { @compileError("blinky is not (yet?) implemented for this target"); diff --git a/port/stmicro/stm32/src/boards/STM32F3DISCOVERY.zig b/port/stmicro/stm32/src/boards/STM32F3DISCOVERY.zig index 9c4ce67a1..e54d8b098 100644 --- a/port/stmicro/stm32/src/boards/STM32F3DISCOVERY.zig +++ b/port/stmicro/stm32/src/boards/STM32F3DISCOVERY.zig @@ -1,6 +1,7 @@ pub const microzig = @import("microzig"); - -pub const cpu_frequency = 8_000_000; +pub const hal = microzig.hal; +pub const rcc = hal.rcc; +pub const pins = hal.pins; pub const pin_map = .{ // circle of LEDs, connected to GPIOE bits 8..15 @@ -23,15 +24,25 @@ pub const pin_map = .{ .LD6 = "PE15", }; -pub fn debug_write(string: []const u8) void { - const uart1 = microzig.core.experimental.Uart(1, .{}).get_or_init(.{ - .baud_rate = 9600, - .data_bits = .eight, - .parity = null, - .stop_bits = .one, - }) catch unreachable; +pub fn init() void { + hal.enable_fpu(); + rcc.enable_hse(8_000_000); + rcc.enable_pll(.HSE, .Div1, .Mul6) catch { + @panic("PLL faile to enable"); + }; + rcc.select_pll_for_sysclk() catch { + @panic("Faile to select sysclk"); + }; +} - const writer = uart1.writer(); - _ = writer.write(string) catch unreachable; - uart1.internal.txflush(); +// Init should come first or the baud_rate would be too fast for the default HSI. +pub fn init_log() void { + _ = (pins.GlobalConfiguration{ + .GPIOC = .{ + .PIN4 = .{ .mode = .{ .alternate_function = .{ .afr = .AF7 } } }, + .PIN5 = .{ .mode = .{ .alternate_function = .{ .afr = .AF7 } } }, + }, + }).apply(); + const uart = try microzig.hal.uart.Uart(.UART1).init(.{ .baud_rate = 115200 }); + microzig.hal.uart.init_logger(&uart); } diff --git a/port/stmicro/stm32/src/hals/STM32F303.zig b/port/stmicro/stm32/src/hals/STM32F303.zig index 7f4a487cb..a9315eafc 100644 --- a/port/stmicro/stm32/src/hals/STM32F303.zig +++ b/port/stmicro/stm32/src/hals/STM32F303.zig @@ -47,33 +47,21 @@ const std = @import("std"); const runtime_safety = std.debug.runtime_safety; const microzig = @import("microzig"); +pub const gpio = @import("STM32F303/gpio.zig"); +pub const uart = @import("STM32F303/uart.zig"); +pub const rcc = @import("STM32F303/rcc.zig"); +pub const i2c = @import("STM32F303/i2c.zig"); + const SPI1 = microzig.peripherals.SPI1; -const RCC = microzig.peripherals.RCC; -const USART1 = microzig.peripherals.USART1; +const RCC = microzig.chip.peripherals.RCC; + const GPIOA = microzig.peripherals.GPIOA; const GPIOB = microzig.peripherals.GPIOB; -const GPIOC = microzig.peripherals.GPIOC; +const GPIOC = microzig.chip.peripherals.GPIOC; const I2C1 = microzig.peripherals.I2C1; pub const cpu = @import("cpu"); -pub const clock = struct { - pub const Domain = enum { - cpu, - ahb, - apb1, - apb2, - }; -}; - -// Default clock frequencies after reset, see top comment for calculation -pub const clock_frequencies = .{ - .cpu = 8_000_000, - .ahb = 8_000_000, - .apb1 = 8_000_000, - .apb2 = 8_000_000, -}; - pub fn parse_pin(comptime spec: []const u8) type { const invalid_format_msg = "The given pin '" ++ spec ++ "' has an invalid format. Pins must follow the format \"P{Port}{Pin}\" scheme."; @@ -98,176 +86,6 @@ fn set_reg_field(reg: anytype, comptime field_name: anytype, value: anytype) voi reg.write(temp); } -pub const gpio = struct { - pub fn set_output(comptime pin: type) void { - set_reg_field(RCC.AHBENR, "IOP" ++ pin.gpio_port_name ++ "EN", 1); - set_reg_field(@field(pin.gpio_port, "MODER"), "MODER" ++ pin.suffix, 0b01); - } - - pub fn set_input(comptime pin: type) void { - set_reg_field(RCC.AHBENR, "IOP" ++ pin.gpio_port_name ++ "EN", 1); - set_reg_field(@field(pin.gpio_port, "MODER"), "MODER" ++ pin.suffix, 0b00); - } - - pub fn read(comptime pin: type) microzig.gpio.State { - const idr_reg = pin.gpio_port.IDR; - const reg_value = @field(idr_reg.read(), "IDR" ++ pin.suffix); // TODO extract to getRegField()? - return @as(microzig.gpio.State, @enumFromInt(reg_value)); - } - - pub fn write(comptime pin: type, state: microzig.gpio.State) void { - switch (state) { - .low => set_reg_field(pin.gpio_port.BRR, "BR" ++ pin.suffix, 1), - .high => set_reg_field(pin.gpio_port.BSRR, "BS" ++ pin.suffix, 1), - } - } -}; - -pub const uart = struct { - pub const DataBits = enum(u4) { - seven = 7, - eight = 8, - }; - - /// uses the values of USART_CR2.STOP - pub const StopBits = enum(u2) { - one = 0b00, - half = 0b01, - two = 0b10, - one_and_half = 0b11, - }; - - /// uses the values of USART_CR1.PS - pub const Parity = enum(u1) { - even = 0, - odd = 1, - }; -}; - -pub fn Uart(comptime index: usize, comptime source_pins: microzig.uart.Pins) type { - if (!(index == 1)) @compileError("TODO: only USART1 is currently supported"); - if (source_pins.tx != null or source_pins.rx != null) - @compileError("TODO: custom pins are not currently supported"); - - return struct { - parity_read_mask: u8, - - const Self = @This(); - - pub fn init(config: microzig.uart.Config) !Self { - // The following must all be written when the USART is disabled (UE=0). - if (USART1.CR1.read().UE == 1) - @panic("Trying to initialize USART1 while it is already enabled"); - // LATER: Alternatively, set UE=0 at this point? Then wait for something? - // Or add a destroy() function which disables the USART? - - // enable the USART1 clock - RCC.APB2ENR.modify(.{ .USART1EN = 1 }); - // enable GPIOC clock - RCC.AHBENR.modify(.{ .IOPCEN = 1 }); - // set PC4+PC5 to alternate function 7, USART1_TX + USART1_RX - GPIOC.MODER.modify(.{ .MODER4 = 0b10, .MODER5 = 0b10 }); - GPIOC.AFRL.modify(.{ .AFRL4 = 7, .AFRL5 = 7 }); - - // clear USART1 configuration to its default - USART1.CR1.raw = 0; - USART1.CR2.raw = 0; - USART1.CR3.raw = 0; - - // set word length - // Per the reference manual, M[1:0] means - // - 00: 8 bits (7 data + 1 parity, or 8 data), probably the chip default - // - 01: 9 bits (8 data + 1 parity) - // - 10: 7 bits (7 data) - // So M1==1 means "7-bit mode" (in which - // "the Smartcard mode, LIN master mode and Auto baud rate [...] are not supported"); - // and M0==1 means 'the 9th bit (not the 8th bit) is the parity bit'. - const m1: u1 = if (config.data_bits == .seven and config.parity == null) 1 else 0; - const m0: u1 = if (config.data_bits == .eight and config.parity != null) 1 else 0; - // Note that .padding0 = bit 28 = .M1 (.svd file bug?), and .M == .M0. - USART1.CR1.modify(.{ .padding0 = m1, .M = m0 }); - - // set parity - if (config.parity) |parity| { - USART1.CR1.modify(.{ .PCE = 1, .PS = @intFromEnum(parity) }); - } else USART1.CR1.modify(.{ .PCE = 0 }); // no parity, probably the chip default - - // set number of stop bits - USART1.CR2.modify(.{ .STOP = @intFromEnum(config.stop_bits) }); - - // set the baud rate - // TODO: Do not use the _board_'s frequency, but the _U(S)ARTx_ frequency - // from the chip, which can be affected by how the board configures the chip. - // In our case, these are accidentally the same at chip reset, - // if the board doesn't configure e.g. an HSE external crystal. - // TODO: Do some checks to see if the baud rate is too high (or perhaps too low) - // TODO: Do a rounding div, instead of a truncating div? - const usartdiv = @as(u16, @intCast(@divTrunc(microzig.clock.get().apb1, config.baud_rate))); - USART1.BRR.raw = usartdiv; - // Above, ignore the BRR struct fields DIV_Mantissa and DIV_Fraction, - // those seem to be for another chipset; .svd file bug? - // TODO: We assume the default OVER8=0 configuration above. - - // enable USART1, and its transmitter and receiver - USART1.CR1.modify(.{ .UE = 1 }); - USART1.CR1.modify(.{ .TE = 1 }); - USART1.CR1.modify(.{ .RE = 1 }); - - // For code simplicity, at cost of one or more register reads, - // we read back the actual configuration from the registers, - // instead of using the `config` values. - return read_from_registers(); - } - - pub fn get_or_init(config: microzig.uart.Config) !Self { - if (USART1.CR1.read().UE == 1) { - // UART1 already enabled, don't reinitialize and disturb things; - // instead read and use the actual configuration. - return read_from_registers(); - } else return init(config); - } - - fn read_from_registers() Self { - const cr1 = USART1.CR1.read(); - // As documented in `init()`, M0==1 means 'the 9th bit (not the 8th bit) is the parity bit'. - // So we always mask away the 9th bit, and if parity is enabled and it is in the 8th bit, - // then we also mask away the 8th bit. - return Self{ .parity_read_mask = if (cr1.PCE == 1 and cr1.M == 0) 0x7F else 0xFF }; - } - - pub fn can_write(self: Self) bool { - _ = self; - return switch (USART1.ISR.read().TXE) { - 1 => true, - 0 => false, - }; - } - - pub fn tx(self: Self, ch: u8) void { - while (!self.can_write()) {} // Wait for Previous transmission - USART1.TDR.modify(ch); - } - - pub fn txflush(_: Self) void { - while (USART1.ISR.read().TC == 0) {} - } - - pub fn can_read(self: Self) bool { - _ = self; - return switch (USART1.ISR.read().RXNE) { - 1 => true, - 0 => false, - }; - } - - pub fn rx(self: Self) u8 { - while (!self.can_read()) {} // Wait till the data is received - const data_with_parity_bit: u9 = USART1.RDR.read().RDR; - return @as(u8, @intCast(data_with_parity_bit & self.parity_read_mask)); - } - }; -} - const enable_stm32f303_debug = false; fn debug_print(comptime format: []const u8, args: anytype) void { @@ -276,6 +94,52 @@ fn debug_print(comptime format: []const u8, args: anytype) void { } } +// Those are missing from the cortex_m4 +// Maybe a specificity from STM that have those FPU unit. +const CPACP = microzig.mmio.Mmio(packed struct(u32) { + reserved1: u20 = 0, + CP10: u2, + CP11: u2, + reserved2: u8 = 0, +}); + +pub const FPCCR = microzig.mmio.Mmio(packed struct(u32) { + LSPACT: u1, + USER: u1, + S: u1, + THREAD: u1, + HFRDY: u1, + MMRDY: u1, + BFRDY: u1, + SFRDY: u1, + MONRDY: u1, + SPLIMVIOL: u1, + UFRDY: u1, + reserved0: u15 = 0, + TS: u1, + CLRONRETS: u1, + CLRONRET: u1, + LSPENS: u1, + LSPEN: u1, + ASPEN: u1, +}); + +pub const missing_peripherals = .{ + .cpacr = @as(*volatile CPACP, @ptrFromInt(0xE000ED88)), + .fpccr = @as(*volatile FPCCR, @ptrFromInt(0xE000EF34)), +}; + +pub fn enable_fpu() void { + missing_peripherals.cpacr.modify(.{ + .CP10 = 0b11, + .CP11 = 0b11, + }); + missing_peripherals.fpccr.modify(.{ + .ASPEN = 1, + .LSPEN = 1, + }); +} + /// This implementation does not use AUTOEND=1 pub fn I2CController(comptime index: usize, comptime source_pins: microzig.i2c.Pins) type { if (!(index == 1)) @compileError("TODO: only I2C1 is currently supported"); diff --git a/port/stmicro/stm32/src/hals/STM32F303/gpio.zig b/port/stmicro/stm32/src/hals/STM32F303/gpio.zig index 6d86810dc..5884fb833 100644 --- a/port/stmicro/stm32/src/hals/STM32F303/gpio.zig +++ b/port/stmicro/stm32/src/hals/STM32F303/gpio.zig @@ -1,56 +1,129 @@ const std = @import("std"); +const assert = std.debug.assert; const microzig = @import("microzig"); -const peripherals = microzig.chip.peripherals; +pub const peripherals = microzig.chip.peripherals; + +const gpio_v2 = microzig.chip.types.peripherals.gpio_v2; +const GPIO = gpio_v2.GPIO; +const MODER = gpio_v2.MODER; +const PUPDR = gpio_v2.PUPDR; +const OT = gpio_v2.OT; +const AFIO = microzig.chip.peripherals.AFIO; + +pub const Function = enum {}; + +pub const Port = enum { + A, + B, + C, + D, + E, + F, + G, +}; pub const Mode = union(enum) { input: InputMode, output: OutputMode, + analog: AnalogMode, + alternate_function: AlternateFunction, }; -pub const InputMode = enum(u2) { - analog, - floating, - pull_up, - pull_down, +pub const InputMode = struct { + resistor: PUPDR, }; -pub const OutputMode = enum(u2) { - push_pull, - open_drain, +pub const OutputMode = struct { resistor: PUPDR, o_type: OT }; + +pub const AnalogMode = enum(u2) { + //todo + _, +}; + +pub const AF = enum(u4) { + AF0, + AF1, + AF2, + AF3, + AF4, + AF5, + AF6, + AF7, }; -// TODO: Add the following -// pub const Speed = enum(u2) { -// low, -// medium, -// high, -// }; +pub const AlternateFunction = struct { + afr: AF, + resistor: PUPDR = .Floating, + o_type: OT = .PushPull, +}; -pub const Pin = struct { - port_id: []const u8, - number_str: []const u8, +// TODO Check the manual +pub const Speed = enum(u2) { + reserved, + max_10MHz, + max_2MHz, + max_50MHz, +}; + +// This is mostly internal to hal for writing configuration. +// Public implementation is provided in the pins.zig file. +pub const Pin = enum(usize) { + _, + + inline fn write_pin_config(gpio: Pin, mode: Mode) void { + const port = gpio.get_port(); + const pin: u5 = @intCast(@intFromEnum(gpio) % 16); + const modMask: u32 = @as(u32, 0b11) << (pin << 1); + const afrMask: u32 = @as(u32, 0b1111) << ((pin % 8) << 2); + + switch (mode) { + .input => |imode| { + port.MODER.write_raw((port.MODER.raw & ~modMask) | @as(u32, @intFromEnum(MODER.Input)) << (pin << 1)); + port.PUPDR.write_raw((port.PUPDR.raw & ~modMask) | @as(u32, @intFromEnum(imode.resistor)) << (pin << 1)); + }, + .output => |omode| { + port.MODER.write_raw((port.MODER.raw & ~modMask) | @as(u32, @intFromEnum(MODER.Output)) << (pin << 1)); + port.OTYPER.write_raw((port.OTYPER.raw & ~gpio.mask()) | @as(u32, @intFromEnum(omode.o_type)) << pin); + port.PUPDR.write_raw((port.PUPDR.raw & ~modMask) | @as(u32, @intFromEnum(omode.resistor)) << (pin << 1)); + }, + .analog => {}, + .alternate_function => |afmode| { + port.MODER.write_raw((port.MODER.raw & ~modMask) | @as(u32, @intFromEnum(MODER.Alternate)) << (pin << 1)); + port.OTYPER.write_raw((port.OTYPER.raw & ~gpio.mask()) | @as(u32, @intFromEnum(afmode.o_type)) << pin); + port.PUPDR.write_raw((port.PUPDR.raw & ~modMask) | @as(u32, @intFromEnum(afmode.resistor)) << (pin << 1)); + const register = if (pin > 7) &port.AFR[1] else &port.AFR[0]; + register.write_raw((register.raw & ~afrMask) | @as(u32, @intFromEnum(afmode.afr)) << ((pin % 8) << 2)); + }, + } + } + + pub fn mask(gpio: Pin) u32 { + const pin: u4 = @intCast(@intFromEnum(gpio) % 16); + return @as(u32, 1) << pin; + } - pub fn init(port_id: []const u8, number_str: []const u8) Pin { - return Pin{ - .port_id = port_id, - .number_str = number_str, - }; + //NOTE: should invalid pins panic or just be ignored? + pub fn get_port(gpio: Pin) *volatile GPIO { + const port: usize = @divFloor(@intFromEnum(gpio), 16); + switch (port) { + 0 => return if (@hasDecl(peripherals, "GPIOA")) peripherals.GPIOA else @panic("Invalid Pin"), + 1 => return if (@hasDecl(peripherals, "GPIOB")) peripherals.GPIOB else @panic("Invalid Pin"), + 2 => return if (@hasDecl(peripherals, "GPIOC")) peripherals.GPIOC else @panic("Invalid Pin"), + 3 => return if (@hasDecl(peripherals, "GPIOD")) peripherals.GPIOD else @panic("Invalid Pin"), + 4 => return if (@hasDecl(peripherals, "GPIOE")) peripherals.GPIOE else @panic("Invalid Pin"), + 5 => return if (@hasDecl(peripherals, "GPIOF")) peripherals.GPIOF else @panic("Invalid Pin"), + 6 => return if (@hasDecl(peripherals, "GPIOG")) peripherals.GPIOG else @panic("Invalid Pin"), + else => @panic("The STM32 only has ports 0..6 (A..G)"), + } } - pub fn configure(comptime self: @This()) void { - const port_peripheral = @field(peripherals, "GPIO" ++ self.port_id); - // TODO: Support input - port_peripheral.MODER.modify_one("MODER[" ++ self.number_str ++ "]", .Output); - // TODO: Support different modes, for input and for output - port_peripheral.OTYPER.modify_one("OT[" ++ self.number_str ++ "]", .PushPull); - // TODO: Support different speeds - port_peripheral.OSPEEDR.modify_one("OSPEEDR[" ++ self.number_str ++ "]", .LowSpeed); - // TODO: Support pull-up / pull-down - port_peripheral.PUPDR.modify_one("PUPDR[" ++ self.number_str ++ "]", .Floating); + pub inline fn set_mode(gpio: Pin, mode: Mode) void { + gpio.write_pin_config(mode); } - pub fn toggle(comptime self: @This()) void { - @field(peripherals, "GPIO" ++ self.port_id).ODR.toggle_one("ODR[" ++ self.number_str ++ "]", .High); + pub fn from_port(port: Port, pin: u4) Pin { + const value: usize = pin + (@as(usize, 16) * @intFromEnum(port)); + return @enumFromInt(value); } }; diff --git a/port/stmicro/stm32/src/hals/STM32F303/pins.zig b/port/stmicro/stm32/src/hals/STM32F303/pins.zig index eae1f0b3b..7a35cc1b6 100644 --- a/port/stmicro/stm32/src/hals/STM32F303/pins.zig +++ b/port/stmicro/stm32/src/hals/STM32F303/pins.zig @@ -1,86 +1,115 @@ const std = @import("std"); +const assert = std.debug.assert; const comptimePrint = std.fmt.comptimePrint; const StructField = std.builtin.Type.StructField; const microzig = @import("microzig"); -const peripherals = microzig.chip.peripherals; + +const RCC = microzig.chip.peripherals.RCC; +const gpio_v2 = microzig.chip.types.peripherals.gpio_v2; +const OSPEEDR = gpio_v2.OSPEEDR; const gpio = @import("gpio.zig"); -/// For now this is always a GPIO pin configuration -const PinConfiguration = struct { - name: ?[:0]const u8 = null, - mode: ?gpio.Mode = null, +pub const Pin = enum { + PIN0, + PIN1, + PIN2, + PIN3, + PIN4, + PIN5, + PIN6, + PIN7, + PIN8, + PIN9, + PIN10, + PIN11, + PIN12, + PIN13, + PIN14, + PIN15, + pub const Configuration = struct { + name: ?[:0]const u8 = null, + mode: ?gpio.Mode = null, + speed: ?OSPEEDR = null, + }; }; -fn GPIO(comptime port: []const u8, comptime num: []const u8, comptime mode: gpio.Mode) type { - if (mode == .input) @compileError("TODO: implement GPIO input mode"); - return switch (mode) { - .input => struct { - const pin = gpio.Pin.init(port, num); +pub const InputGPIO = struct { + pin: gpio.Pin, + pub inline fn read(self: @This()) u1 { + const port = self.pin.get_port(); + return if (port.IDR.raw & gpio.mask() != 0) + 1 + else + 0; + } +}; - pub inline fn read(_: @This()) u1 { - return pin.read(); - } - }, - .output => packed struct { - const pin = gpio.Pin.init(port, num); +pub const OutputGPIO = struct { + pin: gpio.Pin, - pub inline fn put(_: @This(), value: u1) void { - pin.put(value); - } + pub inline fn put(self: @This(), value: u1) void { + var port = self.pin.get_port(); + switch (value) { + 0 => port.BSRR.raw = @intCast(self.pin.mask() << 16), + 1 => port.BSRR.raw = self.pin.mask(), + } + } - pub inline fn toggle(_: @This()) void { - pin.toggle(); - } + pub inline fn low(self: @This()) void { + self.put(0); + } - fn configure(_: @This(), pin_config: PinConfiguration) void { - _ = pin_config; // Later: use for GPIO pin speed etc. - pin.configure(); - } - }, - }; -} + pub inline fn high(self: @This()) void { + self.put(1); + } + + pub inline fn toggle(self: @This()) void { + var port = self.pin.get_port(); + port.ODR.raw ^= self.pin.mask(); + } +}; + +pub const AlternateFunction = struct { + // Empty on perpose it should not be used as a GPIO. +}; + +const Analog = struct { + pin: gpio.Pin, +}; -/// This is a helper empty struct with comptime constants for parsing an STM32 pin name. -/// Example: PinDescription("PE9").gpio_port_id = "E" -/// Example: PinDescription("PA12").gpio_port_number_str = "12" -fn PinDescription(comptime spec: []const u8) type { - const invalid_format_msg = "The given pin '" ++ spec ++ "' has an invalid format. Pins must follow the format \"P{Port}{Pin}\" scheme."; - - if (spec[0] != 'P') - @compileError(invalid_format_msg); - if (spec[1] < 'A' or spec[1] > 'F') - @compileError(invalid_format_msg); - - const gpio_pin_number_int: comptime_int = std.fmt.parseInt(u4, spec[2..], 10) catch @compileError(invalid_format_msg); - return struct { - /// 'A'...'F' - const gpio_port_id = spec[1..2]; - const gpio_pin_number_str = std.fmt.comptimePrint("{d}", .{gpio_pin_number_int}); +pub fn GPIO(comptime mode: gpio.Mode) type { + return switch (mode) { + .input => InputGPIO, + .output => OutputGPIO, + .alternate_function => AlternateFunction, + .analog => Analog, }; } -/// Based on the fields in `config`, returns a struct { -/// PE11: GPIO(...), -/// PF7: GPIO(...), -/// } -/// Later: Also support non-GPIO pins? pub fn Pins(comptime config: GlobalConfiguration) type { comptime { var fields: []const StructField = &.{}; for (@typeInfo(GlobalConfiguration).@"struct".fields) |port_field| { if (@field(config, port_field.name)) |port_config| { - for (@typeInfo(PortConfiguration()).@"struct".fields) |field| { + for (@typeInfo(Port.Configuration).@"struct".fields) |field| { if (@field(port_config, field.name)) |pin_config| { - const D = PinDescription(field.name); - fields = fields ++ &[_]StructField{.{ + var pin_field = StructField{ .is_comptime = false, - .name = pin_config.name orelse field.name, - .type = GPIO(D.gpio_port_id, D.gpio_pin_number_str, pin_config.mode orelse .{ .input = .floating }), .default_value_ptr = null, - .alignment = @alignOf(field.type), - }}; + + // initialized below: + .name = undefined, + .type = undefined, + .alignment = undefined, + }; + + pin_field.name = pin_config.name orelse field.name; + pin_field.type = GPIO(pin_config.mode orelse .{ .input = .{.floating} }); + pin_field.alignment = @alignOf(field.type); + + fields = fields ++ &[_]StructField{pin_field}; } } } @@ -97,59 +126,101 @@ pub fn Pins(comptime config: GlobalConfiguration) type { } } -/// Returns the struct { -/// PA0: ?PinConfiguration = null, -/// ... -/// PF15: ?PinConfiguration = null, -/// } -fn PortConfiguration() type { - @setEvalBranchQuota(200000); - var fields: []const StructField = &.{}; - for ("ABCDEF") |gpio_port_id| { - for (0..16) |gpio_pin_number_int| { - fields = fields ++ &[_]StructField{.{ - .is_comptime = false, - .name = std.fmt.comptimePrint("P{c}{d}", .{ gpio_port_id, gpio_pin_number_int }), - .type = ?PinConfiguration, - .default_value_ptr = &@as(?PinConfiguration, null), - .alignment = @alignOf(?PinConfiguration), - }}; +pub const Port = enum { + GPIOA, + GPIOB, + GPIOC, + GPIOD, + GPIOE, + GPIOF, + GPIOG, + pub const Configuration = struct { + PIN0: ?Pin.Configuration = null, + PIN1: ?Pin.Configuration = null, + PIN2: ?Pin.Configuration = null, + PIN3: ?Pin.Configuration = null, + PIN4: ?Pin.Configuration = null, + PIN5: ?Pin.Configuration = null, + PIN6: ?Pin.Configuration = null, + PIN7: ?Pin.Configuration = null, + PIN8: ?Pin.Configuration = null, + PIN9: ?Pin.Configuration = null, + PIN10: ?Pin.Configuration = null, + PIN11: ?Pin.Configuration = null, + PIN12: ?Pin.Configuration = null, + PIN13: ?Pin.Configuration = null, + PIN14: ?Pin.Configuration = null, + PIN15: ?Pin.Configuration = null, + + comptime { + const pin_field_count = @typeInfo(Pin).@"enum".fields.len; + const config_field_count = @typeInfo(Configuration).@"struct".fields.len; + if (pin_field_count != config_field_count) + @compileError(comptimePrint("{} {}", .{ pin_field_count, config_field_count })); } - } + }; +}; - return @Type(.{ - .@"struct" = .{ - .layout = .auto, - .is_tuple = false, - .fields = fields, - .decls = &.{}, - }, - }); -} pub const GlobalConfiguration = struct { - GPIOA: ?PortConfiguration() = null, - GPIOB: ?PortConfiguration() = null, - GPIOC: ?PortConfiguration() = null, - GPIOD: ?PortConfiguration() = null, - GPIOE: ?PortConfiguration() = null, - GPIOF: ?PortConfiguration() = null, - - pub fn apply(comptime config: @This()) Pins(config) { - const pins: Pins(config) = undefined; // Later: something seems incomplete here... - - inline for (@typeInfo(@This()).@"struct".fields) |port_field| { - const gpio_port_name = port_field.name; - if (@field(config, gpio_port_name)) |port_config| { - peripherals.RCC.AHBENR.modify_one(gpio_port_name ++ "EN", 1); - - inline for (@typeInfo(PortConfiguration()).@"struct".fields) |pin_field| { - if (@field(port_config, pin_field.name)) |pin_config| { - @field(pins, pin_field.name).configure(pin_config); + GPIOA: ?Port.Configuration = null, + GPIOB: ?Port.Configuration = null, + GPIOC: ?Port.Configuration = null, + GPIOD: ?Port.Configuration = null, + GPIOE: ?Port.Configuration = null, + GPIOF: ?Port.Configuration = null, + GPIOG: ?Port.Configuration = null, + + comptime { + const port_field_count = @typeInfo(Port).@"enum".fields.len; + const config_field_count = @typeInfo(GlobalConfiguration).@"struct".fields.len; + if (port_field_count != config_field_count) + @compileError(comptimePrint("{} {}", .{ port_field_count, config_field_count })); + } + + pub fn apply(comptime config: GlobalConfiguration) Pins(config) { + var ret: Pins(config) = undefined; + + comptime var used_gpios: u16 = 0; + + inline for (@typeInfo(GlobalConfiguration).@"struct".fields) |port_field| { + if (@field(config, port_field.name)) |port_config| { + _ = port_config; + const port = @intFromEnum(@field(Port, port_field.name)); + used_gpios |= 1 << port; + } + } + + if (used_gpios != 0) { + RCC.AHBENR.modify(.{ + .GPIOAEN = 0b1 & used_gpios, + .GPIOBEN = 0b1 & (used_gpios >> 1), + .GPIOCEN = 0b1 & (used_gpios >> 2), + .GPIODEN = 0b1 & (used_gpios >> 3), + .GPIOEEN = 0b1 & (used_gpios >> 4), + .GPIOFEN = 0b1 & (used_gpios >> 5), + .GPIOGEN = 0b1 & (used_gpios >> 6), + .GPIOHEN = 0b1 & (used_gpios >> 7), + }); + } + + inline for (@typeInfo(GlobalConfiguration).@"struct".fields) |port_field| { + if (@field(config, port_field.name)) |port_config| { + inline for (@typeInfo(Port.Configuration).@"struct".fields) |field| { + if (@field(port_config, field.name)) |pin_config| { + const port = @intFromEnum(@field(Port, port_field.name)); + var pin = gpio.Pin.from_port(@enumFromInt(port), @intFromEnum(@field(Pin, field.name))); + pin.set_mode(pin_config.mode.?); + switch (pin_config.mode orelse .input) { + .input => @field(ret, pin_config.name orelse field.name) = InputGPIO{ .pin = pin }, + .output => @field(ret, pin_config.name orelse field.name) = OutputGPIO{ .pin = pin }, + .analog => @field(ret, pin_config.name orelse field.name) = Analog{}, + .alternate_function => @field(ret, pin_config.name orelse field.name) = AlternateFunction{}, + } } } } } - return pins; + return ret; } }; diff --git a/port/stmicro/stm32/src/hals/STM32F303/rcc.zig b/port/stmicro/stm32/src/hals/STM32F303/rcc.zig new file mode 100644 index 000000000..bcd9f194c --- /dev/null +++ b/port/stmicro/stm32/src/hals/STM32F303/rcc.zig @@ -0,0 +1,108 @@ +const microzig = @import("microzig"); +const RCC = microzig.chip.peripherals.RCC; +const GPIOF = microzig.chip.peripherals.GPIOF; +const FLASH = microzig.chip.peripherals.FLASH; +const PREDIV = microzig.chip.types.peripherals.rcc_f3v1.PREDIV; +const PLLMUL = microzig.chip.types.peripherals.rcc_f3v1.PLLMUL; + +pub const ClockName = enum { + HSE, + HSI, + PLLCLK, + SYSCLK, + + fn is_for_pll(self: @This()) bool { + return self == .HSE or self == .HSI; + } + + fn is_for_sysclk(self: @This()) bool { + return self != .SYSCLK; + } +}; + +pub const RccErrorConfig = error{ + WrongClockSource, + SourceClockNotInitialized, + OutputPllTooHigh, + PllMustBeEnableFirst, +}; + +pub const Clock = struct { + sys_clk: u32 = 8_000_000, + h_clk: u32 = 8_000_000, + p1_clk: u32 = 8_000_000, + p2_clk: u32 = 8_000_000, + hse: u32 = 0, + hsi: u32 = 8_000_000, + pllout: u32 = 0, + usart1_clk: u32 = 8_000_000, +}; + +pub var current_clock: Clock = .{}; + +pub fn enable_pll(comptime source: ClockName, div: PREDIV, mul: PLLMUL) RccErrorConfig!void { + if (!source.is_for_pll()) { + return RccErrorConfig.WrongClockSource; + } + + if (source == .HSE and current_clock.hse == 0) { + return RccErrorConfig.SourceClockNotInitialized; + } + + const inputClock = if (source == .HSE) current_clock.hse else (current_clock.hsi >> 1); + + const inputDiv = @intFromEnum(div) + 1; + const outputMul = @intFromEnum(mul) + 2; + + const expectedPllOut = @divTrunc(inputClock, inputDiv) * outputMul; + if (expectedPllOut > 72_000_000) { + return RccErrorConfig.OutputPllTooHigh; + } + + RCC.CFGR.modify(.{ .PLLSRC = comptime if (source == .HSE) .HSE_Div_PREDIV else .HSI_Div2, .PLLMUL = mul }); + RCC.CR.modify(.{ .PLLON = 1 }); + + while (RCC.CR.read().PLLRDY != 1) { + asm volatile ("" ::: .{ .memory = true }); + } + + current_clock.pllout = expectedPllOut; +} + +pub fn enable_hse(speed: u32) void { + RCC.CR.modify(.{ .HSEON = 1, .HSEBYP = 1 }); + + while (RCC.CR.read().HSERDY != 1) { + asm volatile ("" ::: .{ .memory = true }); + } + current_clock.hse = speed; +} + +pub fn select_pll_for_sysclk() RccErrorConfig!void { + if (current_clock.pllout == 0) { + return RccErrorConfig.PllMustBeEnableFirst; + } + // Maximum APB low speed domain is 36Nhz, let's divide by 2 + if (current_clock.pllout > 36_000_000) { + RCC.CFGR.modify(.{ .PPRE1 = .Div2 }); + current_clock.p1_clk = current_clock.pllout >> 1; + } else { + current_clock.p1_clk = current_clock.pllout; + } + RCC.CFGR.modify(.{ .SW = .PLL1_P }); + current_clock.sys_clk = current_clock.pllout; + current_clock.h_clk = current_clock.pllout; + current_clock.p2_clk = current_clock.pllout; + current_clock.usart1_clk = current_clock.pllout; + adjust_flash(); +} + +fn adjust_flash() void { + if (current_clock.sys_clk < 24_000_000) { + FLASH.ACR.modify(.{ .LATENCY = .WS0 }); + } else if (current_clock.sys_clk < 42_000_000) { + FLASH.ACR.modify(.{ .LATENCY = .WS1, .PRFTBE = 1 }); + } else { + FLASH.ACR.modify(.{ .LATENCY = .WS2, .PRFTBE = 1 }); + } +} diff --git a/port/stmicro/stm32/src/hals/STM32F303/uart.zig b/port/stmicro/stm32/src/hals/STM32F303/uart.zig new file mode 100644 index 000000000..ff6105796 --- /dev/null +++ b/port/stmicro/stm32/src/hals/STM32F303/uart.zig @@ -0,0 +1,234 @@ +const std = @import("std"); +const rcc = @import("rcc.zig"); +const microzig = @import("microzig"); + +const RCC = microzig.chip.peripherals.RCC; +const usart_t = microzig.chip.type.peripherals.usart_v3.USART; +const STOP = microzig.chip.types.peripherals.usart_v3.STOP; +const USART1 = microzig.chip.peripherals.USART1; +const USART2 = microzig.chip.peripherals.USART2; +const USART3 = microzig.chip.peripherals.USART3; +const UART4 = microzig.chip.peripherals.UART4; +const UART5 = microzig.chip.peripherals.UART5; + +const UartNum = enum(usize) { + UART1, + UART2, + UART3, + UART4, + UART5, +}; +pub const WordBits = enum { + seven, + eight, + nine, +}; +pub const Parity = enum { + none, + even, + odd, +}; + +pub const FlowControl = enum { + none, + CTS, + RTS, + CTS_RTS, +}; + +pub const ConfigError = error{ + InvalidUartNum, + UnsupportedBaudRate, + UnsupportedFlowControl, +}; + +pub const Config = struct { + baud_rate: u32 = 115200, + word_bits: WordBits = .eight, + stop_bits: STOP = .Stop1, + parity: Parity = .none, + flow_control: FlowControl = .none, +}; + +// Make experimental happy +pub const StopBits = STOP; +pub const DataBits = WordBits; + +pub fn Uart(comptime index: UartNum) type { + const regs = switch (index) { + .UART1 => USART1, + .UART2 => USART2, + .UART3 => USART3, + .UART4 => UART4, + .UART5 => UART5, + }; + return struct { + const Self = @This(); + + pub fn init(config: Config) !Self { + switch (index) { + .UART1 => RCC.APB2ENR.modify(.{ .USART1EN = 1 }), + .UART2 => RCC.APB1ENR.modify(.{ .USART2EN = 1 }), + .UART3 => RCC.APB1ENR.modify(.{ .USART3EN = 1 }), + .UART4 => RCC.APB1ENR.modify(.{ .UART4EN = 1 }), + .UART5 => RCC.APB1ENR.modify(.{ .UART5EN = 1 }), + } + + if (regs.CR1.read().UE == 1) + @panic("Trying to initialize USART while it is already enabled"); + + // clear USART1 configuration to its default + regs.CR1.raw = 0; + regs.CR2.raw = 0; + regs.CR3.raw = 0; + + switch (config.word_bits) { + .seven => regs.CR1.modify(.{ .M0 = .Bit8, .M1 = .Bit7 }), + .eight => regs.CR1.modify(.{ .M0 = .Bit8, .M1 = .M0 }), + .nine => regs.CR1.modify(.{ .M0 = .Bit9, .M1 = .M0 }), + } + switch (config.parity) { + .none => regs.CR1.modify(.{ .PCE = 0 }), + .even => regs.CR1.modify(.{ .PCE = 1, .PS = .Even }), + .odd => regs.CR1.modify(.{ .PCE = 1, .PS = .Odd }), + } + + regs.CR2.modify(.{ .STOP = config.stop_bits }); + + // set the baud rate + // TODO: Do not use the _board_'s frequency, but the _U(S)ARTx_ frequency + // from the chip + // TODO: Do some checks to see if the baud rate is too high (or perhaps too low) + const usartdiv = @divTrunc(if (index == .UART1) rcc.current_clock.usart1_clk else rcc.current_clock.p1_clk, config.baud_rate); + regs.BRR.raw = @as(u16, @intCast(usartdiv)); + // TODO: We assume the default OVER8=0 configuration above. + + // enable USART1, and its transmitter and receiver + regs.CR1.modify(.{ .UE = 1 }); + regs.CR1.modify(.{ .TE = 1 }); + regs.CR1.modify(.{ .RE = 1 }); + + return Self{}; + } + + pub fn get_or_init(config: Config) !Self { + if (regs.CR1.read().UE == 1) { + // UART1 already enabled, don't reinitialize and disturb things; + // instead read and use the actual configuration. + return Self{}; + } else return init(config); + } + + pub fn read_mask() u8 { + const cr1 = regs.CR1.read(); + return if (cr1.PCE == 1 and cr1.M0 == .Bit8) 0x7F else 0xFF; + } + + pub fn can_write(self: Self) bool { + _ = self; + return switch (regs.ISR.read().TXE) { + 1 => true, + 0 => false, + }; + } + + pub fn tx(self: Self, ch: u8) void { + while (!self.can_write()) {} // Wait for Previous transmission + regs.TDR.modify(.{ .DR = ch }); + } + + pub fn txflush(_: Self) void { + while (regs.ISR.read().TC == 0) {} + } + + pub fn can_read(self: Self) bool { + _ = self; + return switch (regs.ISR.read().RXNE) { + 1 => true, + 0 => false, + }; + } + + pub fn rx(self: Self) u8 { + while (!self.can_read()) {} // Wait till the data is received + const data_with_parity_bit: u9 = regs.RDR.read().RDR; + return @as(u8, @intCast(data_with_parity_bit & self.read_mask())); + } + + fn writer_fn(self: *const Self, buffer: []const u8) error{}!usize { + for (buffer) |byte| { + self.tx(byte); + } + return buffer.len; + } + }; +} + +pub fn UartWriter(comptime index: UartNum) type { + return struct { + uart: *const Uart(index), + interface: std.Io.Writer, + + pub fn init(uart: *const Uart(index), buffer: []u8) UartWriter(index) { + return .{ + .uart = uart, + .interface = .{ + .vtable = &.{ + .drain = drain, + }, + .buffer = buffer, + }, + }; + } + + pub fn drain(io_w: *std.Io.Writer, data: []const []const u8, splat: usize) std.Io.Writer.Error!usize { + const w: *UartWriter(index) = @alignCast(@fieldParentPtr("interface", io_w)); + var n: u32 = 0; + if (io_w.buffer.len > 0) { + _ = try w.uart.writer_fn(io_w.buffered()); + n += io_w.consumeAll(); + } + for (data[0 .. data.len - 1]) |buf| { + n += try w.uart.writer_fn(buf); + } + const pattern = data[data.len - 1]; + for (0..splat) |_| { + n += try w.uart.writer_fn(pattern); + } + return n; + } + }; +} + +var uart_logger: ?UartWriter(.UART1) = null; + +///Set a specific uart instance to be used for logging. +/// +///Allows system logging over uart via: +///pub const microzig_options = .{ +/// .logFn = hal.uart.log, +///}; +pub fn init_logger(uart: *const Uart(.UART1)) void { + uart_logger = .init(uart, &.{}); + if (uart_logger) |*logger| { + var w = &logger.interface; + w.writeAll("\r\n================ STARTING NEW LOGGER ================\r\n") catch {}; + } +} + +///Disables logging via the uart instance. +pub fn deinit_logger() void { + uart_logger = null; +} + +pub fn log(comptime level: std.log.Level, comptime scope: @TypeOf(.EnumLiteral), comptime format: []const u8, args: anytype) void { + const prefix = comptime level.asText() ++ switch (scope) { + .default => ": ", + else => " (" ++ @tagName(scope) ++ "): ", + }; + + if (uart_logger) |*logger| { + var w = &logger.interface; + w.print(prefix ++ format ++ "\r\n", args) catch {}; + } +}