diff --git a/examples/wch/ch32v/build.zig b/examples/wch/ch32v/build.zig index 1936e5ada..135ed513a 100644 --- a/examples/wch/ch32v/build.zig +++ b/examples/wch/ch32v/build.zig @@ -32,6 +32,7 @@ pub fn build(b: *std.Build) void { .{ .target = mb.ports.ch32v.chips.ch32v203x6, .name = "blinky_systick_ch32v203", .file = "src/blinky_systick.zig" }, .{ .target = mb.ports.ch32v.boards.ch32v203.suzuduino_uno_v1b, .name = "suzuduino_blinky", .file = "src/board_blinky.zig" }, .{ .target = mb.ports.ch32v.boards.ch32v203.lana_tny, .name = "lana_tny_ws2812", .file = "src/ws2812.zig" }, + .{ .target = mb.ports.ch32v.boards.ch32v203.lana_tny, .name = "lana_tny_uart_log", .file = "src/uart_log.zig" }, // CH32V30x .{ .target = mb.ports.ch32v.chips.ch32v303xb, .name = "empty_ch32v303", .file = "src/empty.zig" }, diff --git a/examples/wch/ch32v/src/uart_log.zig b/examples/wch/ch32v/src/uart_log.zig new file mode 100644 index 000000000..d99db5a1c --- /dev/null +++ b/examples/wch/ch32v/src/uart_log.zig @@ -0,0 +1,47 @@ +const std = @import("std"); +const microzig = @import("microzig"); +const hal = microzig.hal; +const time = hal.time; +const gpio = hal.gpio; + +const RCC = microzig.chip.peripherals.RCC; +const AFIO = microzig.chip.peripherals.AFIO; + +const usart = hal.usart.instance.USART2; +const usart_tx_pin = gpio.Pin.init(0, 2); // PA2 + +pub const microzig_options = microzig.Options{ + .log_level = .debug, + .logFn = hal.usart.log, +}; + +pub fn main() !void { + // Board brings up clocks and time + microzig.board.init(); + + // Enable peripheral clocks for USART2 and GPIOA + RCC.APB2PCENR.modify(.{ + .IOPAEN = 1, // Enable GPIOA clock + .AFIOEN = 1, // Enable AFIO clock + }); + RCC.APB1PCENR.modify(.{ + .USART2EN = 1, // Enable USART2 clock + }); + + // Ensure USART2 is NOT remapped (default PA2/PA3, not PD5/PD6) + AFIO.PCFR1.modify(.{ .USART2_RM = 0 }); + + // Configure PA2 as alternate function push-pull for USART2 TX + usart_tx_pin.set_output_mode(.alternate_function_push_pull, .max_50MHz); + + // Initialize USART2 at 115200 baud + usart.apply(.{ .baud_rate = 115200 }); + + hal.usart.init_logger(usart); + + var i: u32 = 0; + while (true) : (i += 1) { + std.log.info("what {}", .{i}); + time.sleep_ms(1000); + } +} diff --git a/port/wch/ch32v/src/hals/ch32v103.zig b/port/wch/ch32v/src/hals/ch32v103.zig index 15214903b..4205ce8b2 100644 --- a/port/wch/ch32v/src/hals/ch32v103.zig +++ b/port/wch/ch32v/src/hals/ch32v103.zig @@ -3,6 +3,7 @@ pub const pins = @import("pins.zig"); pub const gpio = @import("gpio.zig"); pub const clocks = @import("clocks.zig"); pub const time = @import("time.zig"); +pub const usart = @import("usart.zig"); /// Initialize HAL subsystems used by default /// CH32V103: set clock to 48 MHz via HSI PLL; SysTick driver differs on 103, so time is not enabled here. diff --git a/port/wch/ch32v/src/hals/ch32v20x.zig b/port/wch/ch32v/src/hals/ch32v20x.zig index 78871bf05..332c3cf95 100644 --- a/port/wch/ch32v/src/hals/ch32v20x.zig +++ b/port/wch/ch32v/src/hals/ch32v20x.zig @@ -4,6 +4,7 @@ pub const pins = @import("pins.zig"); pub const gpio = @import("gpio.zig"); pub const clocks = @import("clocks.zig"); pub const time = @import("time.zig"); +pub const usart = @import("usart.zig"); pub const default_interrupts: microzig.cpu.InterruptOptions = .{ // Default TIM2 handler provided by the HAL for 1ms timekeeping @@ -18,4 +19,5 @@ test "hal tests" { _ = clocks; _ = gpio; _ = time; + _ = usart; } diff --git a/port/wch/ch32v/src/hals/ch32v30x.zig b/port/wch/ch32v/src/hals/ch32v30x.zig index 6163ac65c..df8d873e3 100644 --- a/port/wch/ch32v/src/hals/ch32v30x.zig +++ b/port/wch/ch32v/src/hals/ch32v30x.zig @@ -3,6 +3,7 @@ pub const pins = @import("pins.zig"); pub const gpio = @import("gpio.zig"); pub const clocks = @import("clocks.zig"); pub const time = @import("time.zig"); +pub const usart = @import("usart.zig"); /// Default interrupt handlers provided by the HAL pub const default_interrupts: microzig.cpu.InterruptOptions = .{ diff --git a/port/wch/ch32v/src/hals/clocks.zig b/port/wch/ch32v/src/hals/clocks.zig index 2fefef6d4..5af68d6f1 100644 --- a/port/wch/ch32v/src/hals/clocks.zig +++ b/port/wch/ch32v/src/hals/clocks.zig @@ -1,9 +1,85 @@ const microzig = @import("microzig"); +const RCC = microzig.chip.peripherals.RCC; +const EXTEND = microzig.chip.peripherals.EXTEND; + +const gpioBlock = enum { + A, + B, + C, + D, +}; + +pub fn enable_gpio_clock(block: gpioBlock) void { + // TODO: How do we know if we need to set the AFIOEN? + switch (block) { + .A => RCC.APB2PCENR.modify(.{ + .IOPAEN = 1, + .AFIOEN = 1, + }), + .B => RCC.APB2PCENR.modify(.{ + .IOPBEN = 1, + .AFIOEN = 1, + }), + .C => RCC.APB2PCENR.modify(.{ + .IOPCEN = 1, + .AFIOEN = 1, + }), + .D => RCC.APB2PCENR.modify(.{ + .IOPDEN = 1, + .AFIOEN = 1, + }), + } +} + +const peripheral = enum { + // APB2 peripherals + USART1, + SPI1, + ADC1, + ADC2, + TIM1, + + // APB1 peripherals + USART2, + USART3, + I2C1, + I2C2, + SPI2, + TIM2, + TIM3, + TIM4, +}; + +pub fn enable_peripheral_clock(p: peripheral) void { + switch (p) { + // APB2 peripherals (high-speed bus) + .USART1 => RCC.APB2PCENR.modify(.{ .USART1EN = 1 }), + .SPI1 => RCC.APB2PCENR.modify(.{ .SPI1EN = 1 }), + .ADC1 => RCC.APB2PCENR.modify(.{ .ADC1EN = 1 }), + .ADC2 => RCC.APB2PCENR.modify(.{ .ADC2EN = 1 }), + .TIM1 => RCC.APB2PCENR.modify(.{ .TIM1EN = 1 }), + + // APB1 peripherals (low-speed bus) + .USART2 => RCC.APB1PCENR.modify(.{ .USART2EN = 1 }), + .USART3 => RCC.APB1PCENR.modify(.{ .USART3EN = 1 }), + .I2C1 => RCC.APB1PCENR.modify(.{ .I2C1EN = 1 }), + .I2C2 => RCC.APB1PCENR.modify(.{ .I2C2EN = 1 }), + .SPI2 => RCC.APB1PCENR.modify(.{ .SPI2EN = 1 }), + .TIM2 => RCC.APB1PCENR.modify(.{ .TIM2EN = 1 }), + .TIM3 => RCC.APB1PCENR.modify(.{ .TIM3EN = 1 }), + .TIM4 => RCC.APB1PCENR.modify(.{ .TIM4EN = 1 }), + } +} + +/// Enable AFIO (Alternate Function I/O) clock +/// Required for pin remapping and external interrupt configuration +pub fn enable_afio_clock() void { + RCC.APB2PCENR.modify(.{ .AFIOEN = 1 }); +} + /// Initialize system clock to 48 MHz using HSI pub fn init_48mhz_hsi() void { - const RCC = microzig.chip.peripherals.RCC; - const EXTEND = microzig.chip.peripherals.EXTEND; // Enable PLL HSI prescaler (HSIPRE bit) EXTEND.EXTEND_CTR.modify(.{ .HSIPRE = 1 }); @@ -29,3 +105,107 @@ pub fn init_48mhz_hsi() void { // Wait for PLL to be used as system clock (SWS should be 2) while (RCC.CFGR0.read().SWS != 2) {} } + +const ClockSpeeds = struct { + sysclk: u32, + hclk: u32, + pclk1: u32, + pclk2: u32, + adcclk: u32, +}; + +// Clock constants +const HSI_VALUE: u32 = 8_000_000; // 8 MHz internal oscillator +const HSE_VALUE: u32 = 8_000_000; // 8 MHz external oscillator (board-dependent) + +// Prescaler lookup table for AHB/APB buses +// Index into this table with the HPRE/PPRE bits, result is the shift amount +const prescaler_table = [16]u8{ 0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9 }; + +// ADC prescaler lookup table (divisor values) +const adc_prescaler_table = [4]u8{ 2, 4, 6, 8 }; + +/// Get the current clock frequencies by reading RCC registers +/// Based on WCH's RCC_GetClocksFreq() implementation +pub fn get_freqs() ClockSpeeds { + var sysclk: u32 = 0; + + // Determine system clock source from SWS (System Clock Switch Status) + const sws = RCC.CFGR0.read().SWS; + + switch (sws) { + 0 => { + // HSI used as system clock + sysclk = HSI_VALUE; + }, + 1 => { + // HSE used as system clock + sysclk = HSE_VALUE; + }, + 2 => { + // PLL used as system clock + const cfgr0 = RCC.CFGR0.read(); + const pllmul_bits = cfgr0.PLLMUL; + const pllsrc = cfgr0.PLLSRC; + + // PLL multiplication factor: PLLMUL bits + 2 + // Special case: if result is 17, it's actually 18 + var pllmul: u32 = @as(u32, pllmul_bits) + 2; + if (pllmul == 17) pllmul = 18; + + if (pllsrc == 0) { + // PLL source is HSI + const hsipre = EXTEND.EXTEND_CTR.read().HSIPRE; + if (hsipre == 1) { + // HSI not divided + sysclk = HSI_VALUE * pllmul; + } else { + // HSI divided by 2 + sysclk = (HSI_VALUE >> 1) * pllmul; + } + } else { + // PLL source is HSE + const pllxtpre = cfgr0.PLLXTPRE; + if (pllxtpre == 1) { + // HSE divided by 2 before PLL + sysclk = (HSE_VALUE >> 1) * pllmul; + } else { + // HSE not divided + sysclk = HSE_VALUE * pllmul; + } + } + }, + else => { + // Default to HSI + sysclk = HSI_VALUE; + }, + } + + // Calculate AHB clock (HCLK) from SYSCLK using HPRE prescaler + const hpre = RCC.CFGR0.read().HPRE; + const hpre_shift = prescaler_table[hpre]; + const hclk = sysclk >> @as(u5, @intCast(hpre_shift)); + + // Calculate APB1 clock (PCLK1) from HCLK using PPRE1 prescaler + const ppre1 = RCC.CFGR0.read().PPRE1; + const ppre1_shift = prescaler_table[ppre1]; + const pclk1 = hclk >> @as(u5, @intCast(ppre1_shift)); + + // Calculate APB2 clock (PCLK2) from HCLK using PPRE2 prescaler + const ppre2 = RCC.CFGR0.read().PPRE2; + const ppre2_shift = prescaler_table[ppre2]; + const pclk2 = hclk >> @as(u5, @intCast(ppre2_shift)); + + // Calculate ADC clock from PCLK2 using ADCPRE + const adcpre = RCC.CFGR0.read().ADCPRE; + const adc_divisor: u32 = adc_prescaler_table[adcpre]; + const adcclk = pclk2 / adc_divisor; + + return .{ + .sysclk = sysclk, + .hclk = hclk, + .pclk1 = pclk1, + .pclk2 = pclk2, + .adcclk = adcclk, + }; +} diff --git a/port/wch/ch32v/src/hals/gpio.zig b/port/wch/ch32v/src/hals/gpio.zig index 13951bb4b..b4286b711 100644 --- a/port/wch/ch32v/src/hals/gpio.zig +++ b/port/wch/ch32v/src/hals/gpio.zig @@ -1,5 +1,6 @@ const microzig = @import("microzig"); pub const peripherals = microzig.chip.peripherals; +const clocks = microzig.hal.clocks; const GPIOA = peripherals.GPIOA; const GPIOB = peripherals.GPIOB; @@ -44,6 +45,11 @@ pub const Pull = enum { down, }; +pub const AlternateFunctionMode = enum { + push_pull, + open_drain, +}; + // NOTE: With this current setup, every time we want to do anythting we go through a switch // Do we want this? // NOTE: How about to use port_config_mask, _value as previous apply function? @@ -109,6 +115,31 @@ pub const Pin = packed struct(u8) { gpio.write_pin_config(config); } + pub inline fn enable_clock(gpio: Pin) void { + // TODO: Cleanup! + clocks.enable_gpio_clock(switch (gpio.get_port()) { + GPIOA => .A, + GPIOB => .B, + GPIOC => .C, + GPIOD => .D, + else => unreachable, + }); + } + + /// Configure pin for alternate function use (e.g., USART, I2C, SPI) + /// Combines enable_clock + set_output_mode for convenience + pub inline fn configure_alternate_function( + gpio: Pin, + mode: AlternateFunctionMode, + speed: Speed, + ) void { + gpio.enable_clock(); + switch (mode) { + .push_pull => gpio.set_output_mode(.alternate_function_push_pull, speed), + .open_drain => gpio.set_output_mode(.alternate_function_open_drain, speed), + } + } + pub inline fn set_pull(gpio: Pin, pull: Pull) void { var port = gpio.get_port(); switch (pull) { diff --git a/port/wch/ch32v/src/hals/pins.zig b/port/wch/ch32v/src/hals/pins.zig index 0b3738570..4bdbaa0f8 100644 --- a/port/wch/ch32v/src/hals/pins.zig +++ b/port/wch/ch32v/src/hals/pins.zig @@ -224,6 +224,7 @@ pub const GlobalConfiguration = struct { const used_gpios = comptime input_gpios | output_gpios; if (used_gpios != 0) { + // Figure out IO port enable bit from name const offset = @as(u3, @intFromEnum(@field(Port, port_field.name))) + 2; RCC.APB2PCENR.raw |= @as(u32, 1 << offset); } @@ -242,7 +243,7 @@ pub const GlobalConfiguration = struct { } } - // Set upll-up and pull-down. + // Set pull-up and pull-down. if (input_gpios != 0) { inline for (@typeInfo(Port.Configuration).@"struct".fields) |field| if (@field(port_config, field.name)) |pin_config| { diff --git a/port/wch/ch32v/src/hals/usart.zig b/port/wch/ch32v/src/hals/usart.zig new file mode 100644 index 000000000..f71655363 --- /dev/null +++ b/port/wch/ch32v/src/hals/usart.zig @@ -0,0 +1,415 @@ +//! +//! This file implements the USART driver for the CH32V chip family +//! +//! Based on the WCH CH32V20x USART peripheral implementation. +//! +const std = @import("std"); +const microzig = @import("microzig"); +const mdf = microzig.drivers; +const hal = microzig.hal; + +const USART1 = microzig.chip.peripherals.USART1; +const USART2 = microzig.chip.peripherals.USART2; +const USART3 = microzig.chip.peripherals.USART3; + +const UsartRegs = microzig.chip.types.peripherals.USART1; + +pub const WordBits = enum { + eight, + nine, +}; + +pub const StopBits = enum { + one, + half, + two, + one_and_half, +}; + +pub const Parity = enum { + none, + even, + odd, +}; + +pub const FlowControl = enum { + none, + CTS, + RTS, + CTS_RTS, +}; + +pub const ConfigError = error{ + UnsupportedBaudRate, +}; + +/// Pin remapping configuration for USART peripherals +/// +/// USART1 has 4 configurations (2 bits: PCFR2.UART1_RM1 + PCFR1.USART1_RM): +/// .default (00): CK=PA8, TX=PA9, RX=PA10, CTS=PA11, RTS=PA12 +/// .remap1 (01): CK=PA8, TX=PB6, RX=PB7, CTS=PA11, RTS=PA12 +/// .remap2 (10): CK=PA10, TX=PB15, RX=PA8, CTS=PA5, RTS=PA9 +/// .remap3 (11): CK=PA5, TX=PA6, RX=PA7, CTS=PC4, RTS=PC5 +/// +/// USART2 has 2 configurations (1 bit: PCFR1.USART2_RM): +/// .default (0): CK=PA4, TX=PA2, RX=PA3, CTS=PA0, RTS=PA1 +/// .remap1 (1): CK=PD7, TX=PD5, RX=PD6, CTS=PD3, RTS=PD4 +/// +/// USART3 has 4 configurations (2 bits: PCFR1.USART3_RM): +/// .default (00): CK=PB12, TX=PB10, RX=PB11, CTS=PB13, RTS=PB14 +/// .remap1 (01): CK=PC12, TX=PC10, RX=PC11, CTS=PB13, RTS=PB14 (partial) +/// .remap3 (11): CK=PD10, TX=PD8, RX=PD9, CTS=PD11, RTS=PD12 (full) +/// +/// See CH32V Reference Manual AFIO_PCFR1/PCFR2 section for details +pub const Remap = enum(u2) { + default = 0b00, + remap1 = 0b01, + remap2 = 0b10, + remap3 = 0b11, +}; + +pub const Config = struct { + baud_rate: u32 = 115200, + word_bits: WordBits = .eight, + stop_bits: StopBits = .one, + parity: Parity = .none, + flow_control: FlowControl = .none, + remap: Remap = .default, +}; + +pub const TransmitError = error{ + Timeout, +}; + +pub const ReceiveError = error{ + OverrunError, + FramingError, + ParityError, + NoiseError, + Timeout, +}; + +pub const instance = struct { + pub const USART1: USART = .USART1; + pub const USART2: USART = .USART2; + pub const USART3: USART = .USART3; + pub fn num(n: u2) USART { + return @enumFromInt(n); + } +}; + +pub const USART = enum(u2) { + USART1 = 0, + USART2 = 1, + USART3 = 2, + _, + + pub const USART_With_Timeout = struct { + instance: USART, + deadline: mdf.time.Deadline, + }; + + pub const Writer = std.io.GenericWriter(USART_With_Timeout, TransmitError, generic_writer_fn); + pub const Reader = std.io.GenericReader(USART_With_Timeout, ReceiveError, generic_reader_fn); + + pub fn writer(usart: USART, deadline: mdf.time.Deadline) Writer { + return .{ .context = .{ .instance = usart, .deadline = deadline } }; + } + + pub fn reader(usart: USART, deadline: mdf.time.Deadline) Reader { + return .{ .context = .{ .instance = usart, .deadline = deadline } }; + } + + pub inline fn get_regs(usart: USART) *volatile UsartRegs { + return switch (@intFromEnum(usart)) { + 0 => USART1, + 1 => USART2, + 2 => USART3, + else => unreachable, + }; + } + + /// Get the peripheral clock frequency for this USART instance + inline fn get_pclk(usart: USART) u32 { + const rcc_clocks = hal.clocks.get_freqs(); + return switch (@intFromEnum(usart)) { + 0 => rcc_clocks.pclk2, // USART1 is on APB2 + 1, 2 => rcc_clocks.pclk1, // USART2/3 are on APB1 + else => unreachable, + }; + } + + /// Apply configuration to the USART peripheral + pub fn apply(comptime usart: USART, comptime config: Config) void { + const regs = usart.get_regs(); + + // Enable peripheral clock + hal.clocks.enable_peripheral_clock(switch (usart) { + .USART1 => .USART1, + .USART2 => .USART2, + .USART3 => .USART3, + // TODO: Add support for other USARTs/UARTs + else => @compileError("USART1,2,3 only supported at the moment"), + }); + + // Configure AFIO remap + hal.clocks.enable_afio_clock(); + const AFIO = microzig.chip.peripherals.AFIO; + const remap_bits = @intFromEnum(config.remap); + + switch (usart) { + .USART1 => { + // USART1: 2 bits split across PCFR1 and PCFR2 + // Bit 0 (LSB) goes to PCFR1.USART1_RM (bit 2) + AFIO.PCFR1.modify(.{ .USART1_RM = @as(u1, @truncate(remap_bits)) }); + // Bit 1 (MSB) goes to PCFR2.UART1_RM1 (bit 26) + AFIO.PCFR2.modify(.{ .UART1_RM1 = @as(u1, @truncate(remap_bits >> 1)) }); + }, + .USART2 => { + // USART2: 1 bit in PCFR1 + AFIO.PCFR1.modify(.{ .USART2_RM = @as(u1, @truncate(remap_bits)) }); + }, + .USART3 => { + // USART3: 2 bits in PCFR1 + AFIO.PCFR1.modify(.{ .USART3_RM = @as(u2, @truncate(remap_bits)) }); + }, + else => unreachable, + } + + // Configure stop bits + const stop_bits_val: u2 = switch (config.stop_bits) { + .one => 0b00, + .half => 0b01, + .two => 0b10, + .one_and_half => 0b11, + }; + regs.CTLR2.modify(.{ .STOP = stop_bits_val }); + + // Configure word length, parity, and mode + const word_length: u1 = switch (config.word_bits) { + .eight => 0, + .nine => 1, + }; + const parity_enable: u1 = if (config.parity == .none) 0 else 1; + const parity_select: u1 = switch (config.parity) { + .even => 0, + .odd => 1, + .none => 0, + }; + + regs.CTLR1.modify(.{ + .M = word_length, + .PCE = parity_enable, + .PS = parity_select, + .TE = 1, // Enable transmitter + .RE = 1, // Enable receiver + }); + + // Configure hardware flow control + const rts_enable: u1 = switch (config.flow_control) { + .RTS, .CTS_RTS => 1, + else => 0, + }; + const cts_enable: u1 = switch (config.flow_control) { + .CTS, .CTS_RTS => 1, + else => 0, + }; + regs.CTLR3.modify(.{ + .RTSE = rts_enable, + .CTSE = cts_enable, + }); + + // Set baud rate + const pclk = usart.get_pclk(); + usart.set_baudrate(config.baud_rate, pclk); + + // Enable USART + regs.CTLR1.modify(.{ .UE = 1 }); + } + + /// Set the baud rate for the USART + /// CH32V always uses 16x oversampling (no OVER8 configuration) + pub fn set_baudrate(usart: USART, baud_rate: u32, pclk: u32) void { + const regs = usart.get_regs(); + + // Calculate baud rate divisor for 16x oversampling + // Formula: BRR = (25 * PCLK) / (4 * baud_rate) + const integerdivider = (25 * pclk) / (4 * baud_rate); + + const mantissa = integerdivider / 100; + const fraction_part = integerdivider - (100 * mantissa); + + const fraction = ((fraction_part * 16 + 50) / 100) & 0x0F; + + const brr_value = (mantissa << 4) | fraction; + regs.BRR.write_raw(@intCast(brr_value)); + } + + /// Check if transmit data register is empty (can write) + pub inline fn is_writeable(usart: USART) bool { + return usart.get_regs().STATR.read().TXE == 1; + } + + /// Check if receive data register is not empty (can read) + pub inline fn is_readable(usart: USART) bool { + return usart.get_regs().STATR.read().RXNE == 1; + } + + /// Check if transmission is complete + pub inline fn is_tx_complete(usart: USART) bool { + return usart.get_regs().STATR.read().TC == 1; + } + + /// Write a single byte (non-blocking) + pub inline fn write_byte(usart: USART, byte: u8) void { + usart.get_regs().DATAR.write_raw(byte); + } + + /// Read a single byte (non-blocking) + pub inline fn read_byte(usart: USART) u8 { + return @intCast(usart.get_regs().DATAR.read().DR); + } + + /// Check for errors and return them + /// TRM 18.10.1 (USARTx_STATR): PE/FE/NE (and IDLE) are cleared by reading the status register + /// then reading the data register. ORE is also cleared by the SR→DR read sequence. Note the TRM + /// caveat for PE: + /// > Before this bit is cleared, the software must wait for RXNE to be set. + /// Our call sites only invoke check_errors() after RXNE is set. + fn check_errors(usart: USART) ReceiveError!void { + const regs = usart.get_regs(); + const status = regs.STATR.read(); + + // Determine which (if any) error occurred, prefer first-match order + var err: ?ReceiveError = null; + if (status.ORE == 1) { + err = ReceiveError.OverrunError; + } else if (status.FE == 1) { + err = ReceiveError.FramingError; + } else if (status.PE == 1) { + err = ReceiveError.ParityError; + } else if (status.NE == 1) { + err = ReceiveError.NoiseError; + } + + // If any error was detected, clear by reading SR then DR once + if (err) |e| { + _ = regs.STATR.read(); + _ = regs.DATAR.read(); + return e; + } + } + + /// Write bytes to USART TX and block until complete + pub fn write_blocking(usart: USART, payload: []const u8, deadline: mdf.time.Deadline) TransmitError!void { + return try usart.writev_blocking(&.{payload}, deadline); + } + + /// Vectored write - writes multiple buffers in sequence + pub fn writev_blocking(usart: USART, payloads: []const []const u8, deadline: mdf.time.Deadline) TransmitError!void { + var iter = microzig.utilities.SliceVector([]const u8).init(payloads).iterator(); + while (iter.next_chunk(null)) |payload| { + for (payload) |byte| { + // Wait for TX register to be empty + while (!usart.is_writeable()) { + if (deadline.is_reached_by(hal.time.get_time_since_boot())) { + return TransmitError.Timeout; + } + } + usart.write_byte(byte); + } + } + + // Wait for transmission to complete + while (!usart.is_tx_complete()) { + if (deadline.is_reached_by(hal.time.get_time_since_boot())) { + return TransmitError.Timeout; + } + } + } + + /// Wrap write_blocking() for use as a GenericWriter + fn generic_writer_fn(usart: USART_With_Timeout, buffer: []const u8) TransmitError!usize { + try usart.instance.write_blocking(buffer, usart.deadline); + return buffer.len; + } + + /// Read bytes from USART RX and block until complete + pub fn read_blocking(usart: USART, buffer: []u8, deadline: mdf.time.Deadline) ReceiveError!void { + return usart.readv_blocking(&.{buffer}, deadline); + } + + /// Vectored read - reads into multiple buffers in sequence + pub fn readv_blocking(usart: USART, buffers: []const []u8, deadline: mdf.time.Deadline) ReceiveError!void { + var iter = microzig.utilities.SliceVector([]u8).init(buffers).iterator(); + while (iter.next_chunk(null)) |buffer| { + for (buffer) |*byte| { + // Wait for RX register to have data + while (!usart.is_readable()) { + if (deadline.is_reached_by(hal.time.get_time_since_boot())) { + return ReceiveError.Timeout; + } + } + + // Check for errors before reading + try usart.check_errors(); + + byte.* = usart.read_byte(); + } + } + } + + /// Read a single byte with timeout + pub fn read_word_blocking(usart: USART, deadline: mdf.time.Deadline) ReceiveError!u8 { + var byte: [1]u8 = undefined; + try usart.read_blocking(&byte, deadline); + return byte[0]; + } + + /// Read a single byte if available, otherwise returns null + pub fn read_word(usart: USART) ReceiveError!?u8 { + if (!usart.is_readable()) return null; + try usart.check_errors(); + return usart.read_byte(); + } + + /// Wraps read_blocking() for use as a GenericReader + fn generic_reader_fn(usart: USART_With_Timeout, buffer: []u8) ReceiveError!usize { + try usart.instance.read_blocking(buffer, usart.deadline); + return buffer.len; + } +}; + +var usart_logger: ?USART.Writer = null; + +/// Set a specific USART instance to be used for logging +pub fn init_logger(usart: USART) void { + usart_logger = usart.writer(.no_deadline); + usart_logger.?.writeAll("\r\n================ STARTING NEW LOGGER ================\r\n") catch {}; +} + +/// Disables logging via the USART instance +pub fn deinit_logger() void { + usart_logger = null; +} + +pub fn log( + comptime level: std.log.Level, + comptime scope: @TypeOf(.enum_literal), + comptime format: []const u8, + args: anytype, +) void { + const level_prefix = comptime "[{}.{:0>6}] " ++ level.asText(); + const prefix = comptime level_prefix ++ switch (scope) { + .default => ": ", + else => " (" ++ @tagName(scope) ++ "): ", + }; + + if (usart_logger) |usart| { + const current_time = hal.time.get_time_since_boot(); + const seconds = current_time.to_us() / std.time.us_per_s; + const microseconds = current_time.to_us() % std.time.us_per_s; + + usart.print(prefix ++ format ++ "\r\n", .{ seconds, microseconds } ++ args) catch {}; + } +}