From df9d0168d42d512426e735c6e14f70c057459c44 Mon Sep 17 00:00:00 2001 From: Kamil Duljas Date: Sun, 19 Oct 2025 22:12:58 +0200 Subject: [PATCH] chips: add stm32l4xx support with interrupt-based USART Add complete support for STM32L4xx family (specifically L476): - Implement clock management (MSI, HSI, PLL, peripheral clocks) - Add RCC, PWR, Flash, GPIO, EXTI, and SYSCFG drivers - Implement interrupt-based USART driver (no DMA) - Add chip-specific traits for clock constants and flash latency - Create stm32l476rg board crate with default peripherals - Add nucleo_l476rg board support with LED, button, GPIO, and console - Implement MSI as default 4MHz system clock source All drivers follow Tock's HIL interfaces and coding standards. Tested on STM32L476RG Nucleo board. --- Cargo.lock | 33 + Cargo.toml | 3 + boards/nucleo_l476rg/.cargo/config.toml | 14 + boards/nucleo_l476rg/Cargo.toml | 26 + boards/nucleo_l476rg/Makefile | 26 + boards/nucleo_l476rg/chip_layout.ld | 19 + boards/nucleo_l476rg/layout.ld | 6 + boards/nucleo_l476rg/src/io.rs | 97 ++ boards/nucleo_l476rg/src/main.rs | 366 ++++ chips/stm32l476rg/Cargo.toml | 18 + chips/stm32l476rg/README.md | 5 + chips/stm32l476rg/src/chip_specs.rs | 42 + chips/stm32l476rg/src/interrupt_service.rs | 36 + chips/stm32l476rg/src/lib.rs | 113 ++ chips/stm32l4xx/Cargo.toml | 23 + chips/stm32l4xx/README.md | 9 + chips/stm32l4xx/src/chip.rs | 135 ++ .../stm32l4xx/src/chip_specific/chip_specs.rs | 14 + .../src/chip_specific/clock_constants.rs | 29 + chips/stm32l4xx/src/chip_specific/flash.rs | 51 + chips/stm32l4xx/src/chip_specific/mod.rs | 14 + chips/stm32l4xx/src/clocks/clocks.rs | 321 ++++ chips/stm32l4xx/src/clocks/hsi.rs | 96 ++ chips/stm32l4xx/src/clocks/mod.rs | 10 + chips/stm32l4xx/src/clocks/msi.rs | 149 ++ chips/stm32l4xx/src/clocks/phclk.rs | 213 +++ chips/stm32l4xx/src/clocks/pll.rs | 241 +++ chips/stm32l4xx/src/exti.rs | 497 ++++++ chips/stm32l4xx/src/flash.rs | 243 +++ chips/stm32l4xx/src/gpio.rs | 1309 +++++++++++++++ chips/stm32l4xx/src/lib.rs | 64 + chips/stm32l4xx/src/nvic.rs | 90 + chips/stm32l4xx/src/pwr.rs | 74 + chips/stm32l4xx/src/rcc.rs | 1481 +++++++++++++++++ chips/stm32l4xx/src/syscfg.rs | 266 +++ chips/stm32l4xx/src/usart.rs | 784 +++++++++ 36 files changed, 6917 insertions(+) create mode 100644 boards/nucleo_l476rg/.cargo/config.toml create mode 100644 boards/nucleo_l476rg/Cargo.toml create mode 100644 boards/nucleo_l476rg/Makefile create mode 100644 boards/nucleo_l476rg/chip_layout.ld create mode 100644 boards/nucleo_l476rg/layout.ld create mode 100644 boards/nucleo_l476rg/src/io.rs create mode 100644 boards/nucleo_l476rg/src/main.rs create mode 100644 chips/stm32l476rg/Cargo.toml create mode 100644 chips/stm32l476rg/README.md create mode 100644 chips/stm32l476rg/src/chip_specs.rs create mode 100644 chips/stm32l476rg/src/interrupt_service.rs create mode 100644 chips/stm32l476rg/src/lib.rs create mode 100644 chips/stm32l4xx/Cargo.toml create mode 100644 chips/stm32l4xx/README.md create mode 100644 chips/stm32l4xx/src/chip.rs create mode 100644 chips/stm32l4xx/src/chip_specific/chip_specs.rs create mode 100644 chips/stm32l4xx/src/chip_specific/clock_constants.rs create mode 100644 chips/stm32l4xx/src/chip_specific/flash.rs create mode 100644 chips/stm32l4xx/src/chip_specific/mod.rs create mode 100644 chips/stm32l4xx/src/clocks/clocks.rs create mode 100644 chips/stm32l4xx/src/clocks/hsi.rs create mode 100644 chips/stm32l4xx/src/clocks/mod.rs create mode 100644 chips/stm32l4xx/src/clocks/msi.rs create mode 100644 chips/stm32l4xx/src/clocks/phclk.rs create mode 100644 chips/stm32l4xx/src/clocks/pll.rs create mode 100644 chips/stm32l4xx/src/exti.rs create mode 100644 chips/stm32l4xx/src/flash.rs create mode 100644 chips/stm32l4xx/src/gpio.rs create mode 100644 chips/stm32l4xx/src/lib.rs create mode 100644 chips/stm32l4xx/src/nvic.rs create mode 100644 chips/stm32l4xx/src/pwr.rs create mode 100644 chips/stm32l4xx/src/rcc.rs create mode 100644 chips/stm32l4xx/src/syscfg.rs create mode 100644 chips/stm32l4xx/src/usart.rs diff --git a/Cargo.lock b/Cargo.lock index ecc08ad68f..168f587a3c 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -1028,6 +1028,20 @@ dependencies = [ "tock_build_scripts", ] +[[package]] +name = "nucleo_l476rg" +version = "0.2.3-dev" +dependencies = [ + "capsules-core", + "capsules-extra", + "capsules-system", + "components", + "cortexm4", + "kernel", + "stm32l476rg", + "tock_build_scripts", +] + [[package]] name = "opaque-debug" version = "0.3.1" @@ -1483,6 +1497,25 @@ dependencies = [ "kernel", ] +[[package]] +name = "stm32l476rg" +version = "0.2.3-dev" +dependencies = [ + "cortexm4f", + "enum_primitive", + "kernel", + "stm32l4xx", +] + +[[package]] +name = "stm32l4xx" +version = "0.2.3-dev" +dependencies = [ + "cortexm4f", + "enum_primitive", + "kernel", +] + [[package]] name = "subtle" version = "2.4.1" diff --git a/Cargo.toml b/Cargo.toml index 85f8ba682e..0c170ad66b 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -39,6 +39,7 @@ members = [ "boards/sma_q3", "boards/nucleo_f429zi", "boards/nucleo_f446re", + "boards/nucleo_l476rg", "boards/particle_boron", "boards/pico_explorer_base", "boards/raspberry_pi_pico", @@ -106,6 +107,8 @@ members = [ "chips/stm32f446re", "chips/stm32f412g", "chips/stm32f4xx", + "chips/stm32l4xx", + "chips/stm32l476rg", "chips/veer_el2", "chips/virtio", "kernel", diff --git a/boards/nucleo_l476rg/.cargo/config.toml b/boards/nucleo_l476rg/.cargo/config.toml new file mode 100644 index 0000000000..e47df29899 --- /dev/null +++ b/boards/nucleo_l476rg/.cargo/config.toml @@ -0,0 +1,14 @@ +# Licensed under the Apache License, Version 2.0 or the MIT License. +# SPDX-License-Identifier: Apache-2.0 OR MIT +# Copyright Tock Contributors 2024. + +include = [ + "../../cargo/tock_flags.toml", + "../../cargo/unstable_flags.toml", +] + +[build] +target = "thumbv7em-none-eabi" + +[unstable] +config-include = true diff --git a/boards/nucleo_l476rg/Cargo.toml b/boards/nucleo_l476rg/Cargo.toml new file mode 100644 index 0000000000..84ef70233b --- /dev/null +++ b/boards/nucleo_l476rg/Cargo.toml @@ -0,0 +1,26 @@ +# Licensed under the Apache License, Version 2.0 or the MIT License. +# SPDX-License-Identifier: Apache-2.0 OR MIT +# Copyright Tock Contributors 2022. + +[package] +name = "nucleo_l476rg" +version.workspace = true +authors.workspace = true +build = "../build.rs" +edition.workspace = true + +[dependencies] +components = { path = "../components" } +cortexm4 = { path = "../../arch/cortex-m4" } +kernel = { path = "../../kernel" } +stm32l476rg = { path = "../../chips/stm32l476rg" } + +capsules-core = { path = "../../capsules/core" } +capsules-extra = { path = "../../capsules/extra" } +capsules-system = { path = "../../capsules/system" } + +[build-dependencies] +tock_build_scripts = { path = "../build_scripts" } + +[lints] +workspace = true diff --git a/boards/nucleo_l476rg/Makefile b/boards/nucleo_l476rg/Makefile new file mode 100644 index 0000000000..fdb53fb173 --- /dev/null +++ b/boards/nucleo_l476rg/Makefile @@ -0,0 +1,26 @@ +# Licensed under the Apache License, Version 2.0 or the MIT License. +# SPDX-License-Identifier: Apache-2.0 OR MIT +# Copyright Tock Contributors 2022. + +# Makefile for building the tock kernel for the NUCLEO-L476RG platform +# + +include ../Makefile.common + +OPENOCD=openocd + +# Default target for installing the kernel. +.PHONY: install +install: flash + +.PHONY: flash-debug +flash-debug: $(TOCK_ROOT_DIRECTORY)target/$(TARGET)/debug/$(PLATFORM).elf + $(OPENOCD) -c "source [find board/st_nucleo_l4.cfg]; init; reset halt; flash write_image erase $<; verify_image $<; reset; shutdown" + +.PHONY: flash +flash: $(TOCK_ROOT_DIRECTORY)target/$(TARGET)/release/$(PLATFORM).elf + $(OPENOCD) -c "source [find board/st_nucleo_l4.cfg]; init; reset halt; flash write_image erase $<; verify_image $<; reset; shutdown" + +.PHONY: program +program: $(TOCK_ROOT_DIRECTORY)target/$(TARGET)/debug/$(PLATFORM).elf + $(error See README.md and update this section accordingly) diff --git a/boards/nucleo_l476rg/chip_layout.ld b/boards/nucleo_l476rg/chip_layout.ld new file mode 100644 index 0000000000..30e1b84610 --- /dev/null +++ b/boards/nucleo_l476rg/chip_layout.ld @@ -0,0 +1,19 @@ +/* Licensed under the Apache License, Version 2.0 or the MIT License. */ +/* SPDX-License-Identifier: Apache-2.0 OR MIT */ +/* Copyright Tock Contributors 2025. */ + +/* Memory layout for the STM32L476RG + * rom = 512KB (LENGTH = 0x00080000) + * kernel = 256KB + * user = 256KB + * ram = 128KB */ + +/* Memories definition */ +MEMORY +{ + rom (rx) : ORIGIN = 0x08000000, LENGTH = 0x00040000 + prog (rx) : ORIGIN = 0x08040000, LENGTH = 0x00040000 + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00020000 +} + +PAGE_SIZE = 2K; diff --git a/boards/nucleo_l476rg/layout.ld b/boards/nucleo_l476rg/layout.ld new file mode 100644 index 0000000000..4faba3611b --- /dev/null +++ b/boards/nucleo_l476rg/layout.ld @@ -0,0 +1,6 @@ +/* Licensed under the Apache License, Version 2.0 or the MIT License. */ +/* SPDX-License-Identifier: Apache-2.0 OR MIT */ +/* Copyright Tock Contributors 2025. */ + +INCLUDE ./chip_layout.ld +INCLUDE tock_kernel_layout.ld diff --git a/boards/nucleo_l476rg/src/io.rs b/boards/nucleo_l476rg/src/io.rs new file mode 100644 index 0000000000..7739fc884d --- /dev/null +++ b/boards/nucleo_l476rg/src/io.rs @@ -0,0 +1,97 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Copyright Tock Contributors 2022. + +use core::fmt::Write; +use core::panic::PanicInfo; +use core::ptr::{addr_of, addr_of_mut}; + +use kernel::debug; +use kernel::debug::IoWrite; +use kernel::hil::led; +use kernel::hil::uart; +use kernel::hil::uart::Configure; + +use stm32l476rg::chip_specs::Stm32l476Specs; +use stm32l476rg::gpio::PinId; + +use crate::CHIP; +use crate::PROCESSES; +use crate::PROCESS_PRINTER; + +/// Writer is used by kernel::debug to panic message to the serial port. +pub struct Writer { + initialized: bool, +} + +/// Global static for debug writer +pub static mut WRITER: Writer = Writer { initialized: false }; + +impl Writer { + /// Indicate that USART has already been initialized. Trying to double + /// initialize USART2 causes STM32xxxx to go into in in-deterministic state. + pub fn set_initialized(&mut self) { + self.initialized = true; + } +} + +impl Write for Writer { + fn write_str(&mut self, s: &str) -> ::core::fmt::Result { + self.write(s.as_bytes()); + Ok(()) + } +} + +impl IoWrite for Writer { + fn write(&mut self, buf: &[u8]) -> usize { + let rcc = stm32l476rg::rcc::Rcc::new(); + let clocks: stm32l476rg::clocks::Clocks = + stm32l476rg::clocks::Clocks::new(&rcc); + let uart = stm32l476rg::usart::Usart::new_usart2(&clocks); + + if !self.initialized { + self.initialized = true; + + let _ = uart.configure(uart::Parameters { + baud_rate: 115200, + stop_bits: uart::StopBits::One, + parity: uart::Parity::None, + hw_flow_control: false, + width: uart::Width::Eight, + }); + } + + for &c in buf { + uart.send_byte(c); + } + buf.len() + } +} + +/// Panic handler. +#[panic_handler] +pub unsafe fn panic_fmt(info: &PanicInfo) -> ! { + // User LD2 is connected to PA05 + // Have to reinitialize several peripherals because otherwise can't access them here. + let rcc = stm32l476rg::rcc::Rcc::new(); + let clocks: stm32l476rg::clocks::Clocks = + stm32l476rg::clocks::Clocks::new(&rcc); + let syscfg = stm32l476rg::syscfg::Syscfg::new(&clocks); + let exti = stm32l476rg::exti::Exti::new(&syscfg); + let pin = stm32l476rg::gpio::Pin::new(PinId::PA05, &exti); + let gpio_ports = stm32l476rg::gpio::GpioPorts::new(&clocks, &exti); + pin.set_ports_ref(&gpio_ports); + let led = &mut led::LedHigh::new(&pin); + + let writer = &mut *addr_of_mut!(WRITER); + + debug::panic( + &mut [led], + writer, + info, + &cortexm4::support::nop, + PROCESSES.unwrap().as_slice(), + &*addr_of!(CHIP), + &*addr_of!(PROCESS_PRINTER), + ) +} diff --git a/boards/nucleo_l476rg/src/main.rs b/boards/nucleo_l476rg/src/main.rs new file mode 100644 index 0000000000..50d9b57889 --- /dev/null +++ b/boards/nucleo_l476rg/src/main.rs @@ -0,0 +1,366 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT + +#![no_std] +#![no_main] +//#![deny(missing_docs)] + +use core::ptr::addr_of_mut; + +use components::gpio::GpioComponent; +use kernel::capabilities; +use kernel::component::Component; +use kernel::hil::gpio::Configure; +use kernel::hil::led::LedHigh; +use kernel::platform::{KernelResources, SyscallDriverLookup}; +use kernel::process::ProcessArray; +use kernel::scheduler::round_robin::RoundRobinSched; +use kernel::{create_capability, debug, static_init}; +use stm32l476rg::chip_specs::Stm32l476Specs; +use stm32l476rg::clocks::msi::MSI_FREQUENCY_MHZ; +use stm32l476rg::gpio::{AlternateFunction, Mode, PinId, PortId}; +use stm32l476rg::interrupt_service::Stm32l476rgDefaultPeripherals; + +/// Support routines for debugging I/O. +pub mod io; + +// Number of concurrent processes this platform supports. +const NUM_PROCS: usize = 4; + +type ChipHw = stm32l476rg::chip::Stm32l4xx<'static, Stm32l476rgDefaultPeripherals<'static>>; + +/// Static variables used by io.rs. +static mut PROCESSES: Option<&'static ProcessArray> = None; + +// Static reference to chip for panic dumps. +static mut CHIP: Option<&'static ChipHw> = None; +// Static reference to process printer for panic dumps. +static mut PROCESS_PRINTER: Option<&'static capsules_system::process_printer::ProcessPrinterText> = + None; + +// How should the kernel respond when a process faults. +const FAULT_RESPONSE: capsules_system::process_policies::PanicFaultPolicy = + capsules_system::process_policies::PanicFaultPolicy {}; + +kernel::stack_size! {0x2000} + +struct Nucleol476RG { + console: &'static capsules_core::console::Console<'static>, + ipc: kernel::ipc::IPC<{ NUM_PROCS as u8 }>, + led: &'static capsules_core::led::LedDriver< + 'static, + LedHigh<'static, stm32l476rg::gpio::Pin<'static>>, + 1, + >, + button: &'static capsules_core::button::Button<'static, stm32l476rg::gpio::Pin<'static>>, + gpio: &'static capsules_core::gpio::GPIO<'static, stm32l476rg::gpio::Pin<'static>>, + + scheduler: &'static RoundRobinSched<'static>, + systick: cortexm4::systick::SysTick, +} + +/// Mapping of integer syscalls to objects that implement syscalls. +impl SyscallDriverLookup for Nucleol476RG { + fn with_driver(&self, driver_num: usize, f: F) -> R + where + F: FnOnce(Option<&dyn kernel::syscall::SyscallDriver>) -> R, + { + match driver_num { + capsules_core::console::DRIVER_NUM => f(Some(self.console)), + capsules_core::led::DRIVER_NUM => f(Some(self.led)), + capsules_core::button::DRIVER_NUM => f(Some(self.button)), + capsules_core::gpio::DRIVER_NUM => f(Some(self.gpio)), + kernel::ipc::DRIVER_NUM => f(Some(&self.ipc)), + _ => f(None), + } + } +} + +impl + KernelResources< + stm32l476rg::chip::Stm32l4xx< + 'static, + stm32l476rg::interrupt_service::Stm32l476rgDefaultPeripherals<'static>, + >, + > for Nucleol476RG +{ + type SyscallDriverLookup = Self; + type SyscallFilter = (); + type ProcessFault = (); + type Scheduler = RoundRobinSched<'static>; + type SchedulerTimer = cortexm4::systick::SysTick; + type WatchDog = (); + type ContextSwitchCallback = (); + + fn syscall_driver_lookup(&self) -> &Self::SyscallDriverLookup { + self + } + fn syscall_filter(&self) -> &Self::SyscallFilter { + &() + } + fn process_fault(&self) -> &Self::ProcessFault { + &() + } + fn scheduler(&self) -> &Self::Scheduler { + self.scheduler + } + fn scheduler_timer(&self) -> &Self::SchedulerTimer { + &self.systick + } + fn watchdog(&self) -> &Self::WatchDog { + &() + } + fn context_switch_callback(&self) -> &Self::ContextSwitchCallback { + &() + } +} + +/// Helper function called during bring-up that configures multiplexed I/O. +unsafe fn set_pin_primary_functions( + syscfg: &stm32l476rg::syscfg::Syscfg, + gpio_ports: &'static stm32l476rg::gpio::GpioPorts<'static>, +) { + syscfg.enable_clock(); + + gpio_ports.get_port_from_port_id(PortId::A).enable_clock(); + gpio_ports.get_port_from_port_id(PortId::B).enable_clock(); + + // User LD2 is connected to PA05. Configure PA05 as `debug_gpio!(0, ...)` + gpio_ports.get_pin(PinId::PA05).map(|pin| { + pin.make_output(); + + // Configure kernel debug gpios as early as possible + kernel::debug::assign_gpios(Some(pin), None, None); + }); + + // PA2 and PA3 (USART2) is connected to ST-LINK virtual COM port + gpio_ports.get_pin(PinId::PA02).map(|pin| { + pin.set_mode(Mode::AlternateFunctionMode); + // AF7 is USART2_TX + pin.set_alternate_function(AlternateFunction::AF7); + }); + gpio_ports.get_pin(PinId::PA03).map(|pin| { + pin.set_mode(Mode::AlternateFunctionMode); + // AF7 is USART2_RX + pin.set_alternate_function(AlternateFunction::AF7); + }); + + gpio_ports.get_port_from_port_id(PortId::C).enable_clock(); + + // button is connected on PC13 + gpio_ports.get_pin(PinId::PC13).map(|pin| { + pin.enable_interrupt(); + }); +} + +/// This is in a separate, inline(never) function so that its stack frame is +/// removed when this function returns. Otherwise, the stack space used for +/// these static_inits is wasted. +#[inline(never)] +unsafe fn start() -> ( + &'static kernel::Kernel, + Nucleol476RG, + &'static stm32l476rg::chip::Stm32l4xx<'static, Stm32l476rgDefaultPeripherals<'static>>, +) { + stm32l476rg::init(); + + // We use the default HSI 16Mhz clock + let rcc = static_init!(stm32l476rg::rcc::Rcc, stm32l476rg::rcc::Rcc::new()); + let clocks = static_init!( + stm32l476rg::clocks::Clocks, + stm32l476rg::clocks::Clocks::new(rcc) + ); + + let syscfg = static_init!( + stm32l476rg::syscfg::Syscfg, + stm32l476rg::syscfg::Syscfg::new(clocks) + ); + let exti = static_init!( + stm32l476rg::exti::Exti, + stm32l476rg::exti::Exti::new(syscfg) + ); + + let peripherals = static_init!( + Stm32l476rgDefaultPeripherals, + Stm32l476rgDefaultPeripherals::new(clocks, exti) + ); + peripherals.init(); + let base_peripherals = &peripherals.stm32l4; + + set_pin_primary_functions(syscfg, &base_peripherals.gpio_ports); + + // Create an array to hold process references. + let processes = components::process_array::ProcessArrayComponent::new() + .finalize(components::process_array_component_static!(NUM_PROCS)); + PROCESSES = Some(processes); + + // Setup space to store the core kernel data structure. + let board_kernel = static_init!(kernel::Kernel, kernel::Kernel::new(processes.as_slice())); + + let chip = static_init!( + stm32l476rg::chip::Stm32l4xx, + stm32l476rg::chip::Stm32l4xx::new(peripherals) + ); + CHIP = Some(chip); + + // UART + + cortexm4::nvic::Nvic::new(stm32l476rg::nvic::USART2).enable(); + // Create a shared UART channel for kernel debug. + base_peripherals.usart2.enable_clock(); + let uart_mux = components::console::UartMuxComponent::new(&base_peripherals.usart2, 115200) + .finalize(components::uart_mux_component_static!()); + + // `finalize()` configures the underlying USART, so we need to + // tell `send_byte()` not to configure the USART again. + (*addr_of_mut!(io::WRITER)).set_initialized(); + + // Create capabilities that the board needs to call certain protected kernel + // functions. + let memory_allocation_capability = create_capability!(capabilities::MemoryAllocationCapability); + let process_management_capability = + create_capability!(capabilities::ProcessManagementCapability); + + // Setup the console. + let console = components::console::ConsoleComponent::new( + board_kernel, + capsules_core::console::DRIVER_NUM, + uart_mux, + ) + .finalize(components::console_component_static!()); + // Create the debugger object that handles calls to `debug!()`. + components::debug_writer::DebugWriterComponent::new::< + ::ThreadIdProvider, + >( + uart_mux, + create_capability!(capabilities::SetDebugWriterCapability), + ) + .finalize(components::debug_writer_component_static!()); + + // LEDs + let gpio_ports = &base_peripherals.gpio_ports; + + // Clock to Port A is enabled in `set_pin_primary_functions()` + let led = components::led::LedsComponent::new().finalize(components::led_component_static!( + LedHigh<'static, stm32l476rg::gpio::Pin>, + LedHigh::new(gpio_ports.get_pin(stm32l476rg::gpio::PinId::PA05).unwrap()), + )); + + // BUTTONs + let button = components::button::ButtonComponent::new( + board_kernel, + capsules_core::button::DRIVER_NUM, + components::button_component_helper!( + stm32l476rg::gpio::Pin, + ( + gpio_ports.get_pin(stm32l476rg::gpio::PinId::PC13).unwrap(), + kernel::hil::gpio::ActivationMode::ActiveLow, + kernel::hil::gpio::FloatingState::PullNone + ) + ), + ) + .finalize(components::button_component_static!(stm32l476rg::gpio::Pin)); + + let process_printer = components::process_printer::ProcessPrinterTextComponent::new() + .finalize(components::process_printer_text_component_static!()); + PROCESS_PRINTER = Some(process_printer); + + // GPIO + let gpio = GpioComponent::new( + board_kernel, + capsules_core::gpio::DRIVER_NUM, + components::gpio_component_helper!( + stm32l476rg::gpio::Pin, + // Arduino like RX/TX + // 0 => gpio_ports.get_pin(PinId::PA03).unwrap(), //D0 + // 1 => gpio_ports.get_pin(PinId::PA02).unwrap(), //D1 + 2 => gpio_ports.get_pin(PinId::PA10).unwrap(), //D2 + 3 => gpio_ports.get_pin(PinId::PB03).unwrap(), //D3 + 4 => gpio_ports.get_pin(PinId::PB05).unwrap(), //D4 + 5 => gpio_ports.get_pin(PinId::PB04).unwrap(), //D5 + 6 => gpio_ports.get_pin(PinId::PB10).unwrap(), //D6 + 7 => gpio_ports.get_pin(PinId::PA08).unwrap(), //D7 + 8 => gpio_ports.get_pin(PinId::PA09).unwrap(), //D8 + 9 => gpio_ports.get_pin(PinId::PC07).unwrap(), //D9 + 10 => gpio_ports.get_pin(PinId::PB06).unwrap(), //D10 + 11 => gpio_ports.get_pin(PinId::PA07).unwrap(), //D11 + 12 => gpio_ports.get_pin(PinId::PA06).unwrap(), //D12 + 13 => gpio_ports.get_pin(PinId::PA05).unwrap(), //D13 + 14 => gpio_ports.get_pin(PinId::PB09).unwrap(), //D14 + 15 => gpio_ports.get_pin(PinId::PB08).unwrap(), //D15 + ), + ) + .finalize(components::gpio_component_static!(stm32l476rg::gpio::Pin)); + + let scheduler = components::sched::round_robin::RoundRobinComponent::new(processes) + .finalize(components::round_robin_component_static!(NUM_PROCS)); + + let nucleo_l476rg = Nucleol476RG { + console, + ipc: kernel::ipc::IPC::new( + board_kernel, + kernel::ipc::DRIVER_NUM, + &memory_allocation_capability, + ), + led, + button, + gpio, + scheduler, + systick: cortexm4::systick::SysTick::new_with_calibration( + (MSI_FREQUENCY_MHZ * 1_000_000) as u32, + ), + }; + + // Optional kernel tests + // + // See comment in `boards/imix/src/main.rs` + // virtual_uart_rx_test::run_virtual_uart_receive(mux_uart); + + // Run MSI clock tests + stm32l476rg::clocks::msi::tests::run(&clocks.msi); + + debug!("Initialization complete. Entering main loop"); + + // These symbols are defined in the linker script. + extern "C" { + /// Beginning of the ROM region containing app images. + static _sapps: u8; + /// End of the ROM region containing app images. + static _eapps: u8; + /// Beginning of the RAM region for app memory. + static mut _sappmem: u8; + /// End of the RAM region for app memory. + static _eappmem: u8; + } + + kernel::process::load_processes( + board_kernel, + chip, + core::slice::from_raw_parts( + core::ptr::addr_of!(_sapps), + core::ptr::addr_of!(_eapps) as usize - core::ptr::addr_of!(_sapps) as usize, + ), + core::slice::from_raw_parts_mut( + core::ptr::addr_of_mut!(_sappmem), + core::ptr::addr_of!(_eappmem) as usize - core::ptr::addr_of!(_sappmem) as usize, + ), + &FAULT_RESPONSE, + &process_management_capability, + ) + .unwrap_or_else(|err| { + debug!("Error loading processes!"); + debug!("{:?}", err); + }); + + (board_kernel, nucleo_l476rg, chip) +} + +/// Main function called after RAM initialized. +#[no_mangle] +pub unsafe fn main() { + let main_loop_capability = create_capability!(capabilities::MainLoopCapability); + + let (board_kernel, platform, chip) = start(); + + board_kernel.kernel_loop(&platform, chip, Some(&platform.ipc), &main_loop_capability); +} diff --git a/chips/stm32l476rg/Cargo.toml b/chips/stm32l476rg/Cargo.toml new file mode 100644 index 0000000000..e266179ce4 --- /dev/null +++ b/chips/stm32l476rg/Cargo.toml @@ -0,0 +1,18 @@ +# Licensed under the Apache License, Version 2.0 or the MIT License. +# SPDX-License-Identifier: Apache-2.0 OR MIT +# Copyright Tock Contributors 2025. + +[package] +name = "stm32l476rg" +version.workspace = true +authors.workspace = true +edition.workspace = true + +[dependencies] +cortexm4f = { path = "../../arch/cortex-m4f" } +kernel = { path = "../../kernel" } +stm32l4xx = { path = "../stm32l4xx", features = ["stm32l476"] } +enum_primitive = { path = "../../libraries/enum_primitive" } + +[lints] +workspace = true diff --git a/chips/stm32l476rg/README.md b/chips/stm32l476rg/README.md new file mode 100644 index 0000000000..a90c3bd5cd --- /dev/null +++ b/chips/stm32l476rg/README.md @@ -0,0 +1,5 @@ +# ST Micro stm32l476rg MCU + +Builds upon the `stm32l4xx` crate and includes hardware setup that is specific to this version of +the stm32l4xx series. Boards that include an stm32l476rg MCU should use this crate as a dependency +and not the `stm32l4xx` crate. diff --git a/chips/stm32l476rg/src/chip_specs.rs b/chips/stm32l476rg/src/chip_specs.rs new file mode 100644 index 0000000000..7a5244c331 --- /dev/null +++ b/chips/stm32l476rg/src/chip_specs.rs @@ -0,0 +1,42 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +//! STM32L476 specifications + +use stm32l4xx::chip_specific::clock_constants::{PllConstants, SystemClockConstants}; +use stm32l4xx::chip_specific::flash::{FlashChipSpecific, FlashLatency5}; + +pub enum Stm32l476Specs {} + +impl PllConstants for Stm32l476Specs {} + +impl SystemClockConstants for Stm32l476Specs {} + +impl FlashChipSpecific for Stm32l476Specs { + type FlashLatency = FlashLatency5; + + fn get_number_wait_cycles_based_on_frequency_and_voltage( + frequency_mhz: usize, + vos: usize, + ) -> Self::FlashLatency { + match vos { + 1 => match frequency_mhz { + 0..=16 => Self::FlashLatency::Latency0, + 17..=32 => Self::FlashLatency::Latency1, + 33..=48 => Self::FlashLatency::Latency2, + 49..=64 => Self::FlashLatency::Latency3, + 65..=80 => Self::FlashLatency::Latency4, + _ => Self::FlashLatency::Latency5, + }, + 2 => match frequency_mhz { + 0..=6 => Self::FlashLatency::Latency0, + 7..=12 => Self::FlashLatency::Latency1, + 13..=18 => Self::FlashLatency::Latency2, + 19..=26 => Self::FlashLatency::Latency3, + _ => Self::FlashLatency::Latency5, + }, + _ => panic!("Unexpected VOS!"), + } + } +} diff --git a/chips/stm32l476rg/src/interrupt_service.rs b/chips/stm32l476rg/src/interrupt_service.rs new file mode 100644 index 0000000000..ebd0a9e527 --- /dev/null +++ b/chips/stm32l476rg/src/interrupt_service.rs @@ -0,0 +1,36 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +use crate::chip_specs::Stm32l476Specs; +use stm32l4xx::chip::Stm32l4xxDefaultPeripherals; + +pub struct Stm32l476rgDefaultPeripherals<'a> { + pub stm32l4: Stm32l4xxDefaultPeripherals<'a, Stm32l476Specs>, + // Once implemented, place Stm32l476rg specific peripherals here +} + +impl<'a> Stm32l476rgDefaultPeripherals<'a> { + pub unsafe fn new( + clocks: &'a crate::clocks::Clocks<'a, Stm32l476Specs>, + exti: &'a crate::exti::Exti<'a>, + ) -> Self { + Self { + stm32l4: Stm32l4xxDefaultPeripherals::new(clocks, exti), + } + } + // Necessary for setting up circular dependencies & registering deferred + // calls + pub fn init(&'static self) { + self.stm32l4.setup_circular_deps(); + } +} +impl kernel::platform::chip::InterruptService for Stm32l476rgDefaultPeripherals<'_> { + unsafe fn service_interrupt(&self, interrupt: u32) -> bool { + #[allow(clippy::match_single_binding)] + match interrupt { + // put Stm32l476rg specific interrupts here + _ => self.stm32l4.service_interrupt(interrupt), + } + } +} diff --git a/chips/stm32l476rg/src/lib.rs b/chips/stm32l476rg/src/lib.rs new file mode 100644 index 0000000000..0d2ae02f00 --- /dev/null +++ b/chips/stm32l476rg/src/lib.rs @@ -0,0 +1,113 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +#![no_std] + +pub use stm32l4xx::{chip, clocks, exti, flash, gpio, nvic, rcc, syscfg, usart}; + +pub mod chip_specs; +pub mod interrupt_service; +//pub mod stm32l476rg_nvic; + +use cortexm4f::{unhandled_interrupt, CortexM4F, CortexMVariant}; + +// STM32L476rg has total of 82 interrupts +// Extracted from `CMSIS/Device/ST/STM32L4xx/Include/stm32l476xx.h` +// NOTE: There are missing IRQn between 0 and 81 +#[cfg_attr(all(target_arch = "arm", target_os = "none"), link_section = ".irqs")] +// `used` ensures that the symbol is kept until the final binary. However, as of +// May 2020, due to the compilation process, there must be some other compiled +// code here to make sure the object file is kept around. That means at minimum +// there must be an `init()` function here so that compiler does not just ignore +// the `IRQS` object. See https://github.com/rust-lang/rust/issues/56639 for a +// related discussion. +#[cfg_attr(all(target_arch = "arm", target_os = "none"), used)] +pub static IRQS: [unsafe extern "C" fn(); 82] = [ + CortexM4F::GENERIC_ISR, // Window WatchDog Interrupt (0) + CortexM4F::GENERIC_ISR, // PVD/PVM1/PVM2/PVM3/PVM4 through EXTI Line detection Interrupts (1) + CortexM4F::GENERIC_ISR, // Tamper and TimeStamp interrupts through the EXTI line (2) + CortexM4F::GENERIC_ISR, // RTC Wakeup interrupt through the EXTI line (3) + CortexM4F::GENERIC_ISR, // FLASH global Interrupt (4) + CortexM4F::GENERIC_ISR, // RCC global Interrupt (5) + CortexM4F::GENERIC_ISR, // EXTI Line0 Interrupt (6) + CortexM4F::GENERIC_ISR, // EXTI Line1 Interrupt (7) + CortexM4F::GENERIC_ISR, // EXTI Line2 Interrupt (8) + CortexM4F::GENERIC_ISR, // EXTI Line3 Interrupt (9) + CortexM4F::GENERIC_ISR, // EXTI Line4 Interrupt (10) + CortexM4F::GENERIC_ISR, // DMA1 Channel 1 global Interrupt (11) + CortexM4F::GENERIC_ISR, // DMA1 Channel 2 global Interrupt (12) + CortexM4F::GENERIC_ISR, // DMA1 Channel 3 global Interrupt (13) + CortexM4F::GENERIC_ISR, // DMA1 Channel 4 global Interrupt (14) + CortexM4F::GENERIC_ISR, // DMA1 Channel 5 global Interrupt (15) + CortexM4F::GENERIC_ISR, // DMA1 Channel 6 global Interrupt (16) + CortexM4F::GENERIC_ISR, // DMA1 Channel 7 global Interrupt (17) + CortexM4F::GENERIC_ISR, // ADC1, ADC2 SAR global Interrupts (18) + CortexM4F::GENERIC_ISR, // CAN1 TX Interrupt (19) + CortexM4F::GENERIC_ISR, // CAN1 RX0 Interrupt (20) + CortexM4F::GENERIC_ISR, // CAN1 RX1 Interrupt (21) + CortexM4F::GENERIC_ISR, // CAN1 SCE Interrupt (22) + CortexM4F::GENERIC_ISR, // External Line[9:5] Interrupts (23) + CortexM4F::GENERIC_ISR, // TIM1 Break interrupt and TIM15 global interrupt (24) + CortexM4F::GENERIC_ISR, // TIM1 Update Interrupt and TIM16 global interrupt (25) + CortexM4F::GENERIC_ISR, // TIM1 Trigger and Commutation Interrupt and TIM17 global interrupt (26) + CortexM4F::GENERIC_ISR, // TIM1 Capture Compare Interrupt (27) + CortexM4F::GENERIC_ISR, // TIM2 global Interrupt (28) + CortexM4F::GENERIC_ISR, // TIM3 global Interrupt (29) + CortexM4F::GENERIC_ISR, // TIM4 global Interrupt (30) + CortexM4F::GENERIC_ISR, // I2C1 Event Interrupt (31) + CortexM4F::GENERIC_ISR, // I2C1 Error Interrupt (32) + CortexM4F::GENERIC_ISR, // I2C2 Event Interrupt (33) + CortexM4F::GENERIC_ISR, // I2C2 Error Interrupt (34) + CortexM4F::GENERIC_ISR, // SPI1 global Interrupt (35) + CortexM4F::GENERIC_ISR, // SPI2 global Interrupt (36) + CortexM4F::GENERIC_ISR, // USART1 global Interrupt (37) + CortexM4F::GENERIC_ISR, // USART2 global Interrupt (38) + CortexM4F::GENERIC_ISR, // USART3 global Interrupt (39) + CortexM4F::GENERIC_ISR, // External Line[15:10] Interrupts (40) + CortexM4F::GENERIC_ISR, // RTC Alarm (A and B) through EXTI Line Interrupt (41) + CortexM4F::GENERIC_ISR, // DFSDM1 Filter 3 global Interrupt (42) + CortexM4F::GENERIC_ISR, // TIM8 Break Interrupt (43) + CortexM4F::GENERIC_ISR, // TIM8 Update Interrupt (44) + CortexM4F::GENERIC_ISR, // TIM8 Trigger and Commutation Interrupt (45) + CortexM4F::GENERIC_ISR, // TIM8 Capture Compare Interrupt (46) + CortexM4F::GENERIC_ISR, // ADC3 global Interrupt (47) + CortexM4F::GENERIC_ISR, // FMC global Interrupt (48) + CortexM4F::GENERIC_ISR, // SDMMC1 global Interrupt (49) + CortexM4F::GENERIC_ISR, // TIM5 global Interrupt (50) + CortexM4F::GENERIC_ISR, // SPI3 global Interrupt (51) + CortexM4F::GENERIC_ISR, // UART4 global Interrupt (52) + CortexM4F::GENERIC_ISR, // UART5 global Interrupt (53) + CortexM4F::GENERIC_ISR, // TIM6 global and DAC1&2 underrun error interrupts (54) + CortexM4F::GENERIC_ISR, // TIM7 global interrupt (55) + CortexM4F::GENERIC_ISR, // DMA2 Channel 1 global Interrupt (56) + CortexM4F::GENERIC_ISR, // DMA2 Channel 2 global Interrupt (57) + CortexM4F::GENERIC_ISR, // DMA2 Channel 3 global Interrupt (58) + CortexM4F::GENERIC_ISR, // DMA2 Channel 4 global Interrupt (59) + CortexM4F::GENERIC_ISR, // DMA2 Channel 5 global Interrupt (60) + CortexM4F::GENERIC_ISR, // DFSDM1 Filter 0 global Interrupt (61) + CortexM4F::GENERIC_ISR, // DFSDM1 Filter 1 global Interrupt (62) + CortexM4F::GENERIC_ISR, // DFSDM1 Filter 2 global Interrupt (63) + CortexM4F::GENERIC_ISR, // COMP1 and COMP2 Interrupts (64) + CortexM4F::GENERIC_ISR, // LP TIM1 interrupt (65) + CortexM4F::GENERIC_ISR, // LP TIM2 interrupt (66) + CortexM4F::GENERIC_ISR, // USB OTG FS global Interrupt (67) + CortexM4F::GENERIC_ISR, // DMA2 Channel 6 global interrupt (68) + CortexM4F::GENERIC_ISR, // DMA2 Channel 7 global interrupt (69) + CortexM4F::GENERIC_ISR, // LP UART1 interrupt (70) + CortexM4F::GENERIC_ISR, // Quad SPI global interrupt (71) + CortexM4F::GENERIC_ISR, // I2C3 event interrupt (72) + CortexM4F::GENERIC_ISR, // I2C3 error interrupt (73) + CortexM4F::GENERIC_ISR, // Serial Audio Interface 1 global interrupt (74) + CortexM4F::GENERIC_ISR, // Serial Audio Interface 2 global interrupt (75) + CortexM4F::GENERIC_ISR, // Serial Wire Interface 1 global interrupt (76) + CortexM4F::GENERIC_ISR, // Touch Sense Controller global interrupt (77) + CortexM4F::GENERIC_ISR, // LCD global interrupt (78) + unhandled_interrupt, // (79) + CortexM4F::GENERIC_ISR, // RNG global interrupt (80) + CortexM4F::GENERIC_ISR, // FPU global interrupt (81) +]; + +pub unsafe fn init() { + stm32l4xx::init(); +} diff --git a/chips/stm32l4xx/Cargo.toml b/chips/stm32l4xx/Cargo.toml new file mode 100644 index 0000000000..40d22eb69e --- /dev/null +++ b/chips/stm32l4xx/Cargo.toml @@ -0,0 +1,23 @@ +# Licensed under the Apache License, Version 2.0 or the MIT License. +# SPDX-License-Identifier: Apache-2.0 OR MIT +# Copyright Tock Contributors 2025. + +[package] +name = "stm32l4xx" +version.workspace = true +authors.workspace = true +edition.workspace = true + +[dependencies] +cortexm4f = { path = "../../arch/cortex-m4f" } +enum_primitive = { path = "../../libraries/enum_primitive" } +kernel = { path = "../../kernel" } + +[features] +# Currently, Tock supports only these chips. +# When a new chip is added, add its identifier here and inside +# the chip's crate as a feature for the dependency. +stm32l476 = [] + +[lints] +workspace = true diff --git a/chips/stm32l4xx/README.md b/chips/stm32l4xx/README.md new file mode 100644 index 0000000000..493946eea4 --- /dev/null +++ b/chips/stm32l4xx/README.md @@ -0,0 +1,9 @@ +For STM32L4 series micro controllers + + +## Links +### ST STM32L476RG + +* [General information](https://www.st.com/en/microcontrollers/stm32l476rg.html) +* [Datasheet](https://www.st.com/resource/en/datasheet/stm32l476rg.pdf) +* [Reference Manual](https://www.st.com/resource/en/reference_manual/rm0351-stm32l47xxx-stm32l48xxx-stm32l49xxx-and-stm32l4axxx-advanced-armbased-32bit-mcus-stmicroelectronics.pdf) diff --git a/chips/stm32l4xx/src/chip.rs b/chips/stm32l4xx/src/chip.rs new file mode 100644 index 0000000000..6138a10669 --- /dev/null +++ b/chips/stm32l4xx/src/chip.rs @@ -0,0 +1,135 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +use core::fmt::Write; +use cortexm4f::{CortexM4F, CortexMVariant}; +use kernel::platform::chip::Chip; +use kernel::platform::chip::InterruptService; + +use crate::nvic; + +use crate::chip_specific::chip_specs::ChipSpecs as ChipSpecsTrait; + +pub struct Stm32l4xx<'a, I: InterruptService + 'a> { + mpu: cortexm4f::mpu::MPU, + userspace_kernel_boundary: cortexm4f::syscall::SysCall, + interrupt_service: &'a I, +} + +pub struct Stm32l4xxDefaultPeripherals<'a, ChipSpecs> { + pub gpio_ports: crate::gpio::GpioPorts<'a>, + pub clocks: &'a crate::clocks::Clocks<'a, ChipSpecs>, + pub flash: crate::flash::Flash, + pub exti: &'a crate::exti::Exti<'a>, + pub usart1: crate::usart::Usart<'a>, + pub usart2: crate::usart::Usart<'a>, + pub usart3: crate::usart::Usart<'a>, +} + +impl<'a, ChipSpecs: ChipSpecsTrait> Stm32l4xxDefaultPeripherals<'a, ChipSpecs> { + pub fn new( + clocks: &'a crate::clocks::Clocks<'a, ChipSpecs>, + exti: &'a crate::exti::Exti<'a>, + ) -> Self { + let pwr = crate::pwr::Pwr::new(); + Self { + clocks, + gpio_ports: crate::gpio::GpioPorts::new(clocks, exti), + flash: crate::flash::Flash::new(pwr), + exti, + usart1: crate::usart::Usart::new_usart1(clocks), + usart2: crate::usart::Usart::new_usart2(clocks), + usart3: crate::usart::Usart::new_usart3(clocks), + } + } + + pub fn setup_circular_deps(&'static self) { + self.clocks.set_flash(&self.flash); + self.gpio_ports.setup_circular_deps(); + + kernel::deferred_call::DeferredCallClient::register(&self.usart1); + kernel::deferred_call::DeferredCallClient::register(&self.usart2); + kernel::deferred_call::DeferredCallClient::register(&self.usart3); + } +} + +impl InterruptService for Stm32l4xxDefaultPeripherals<'_, ChipSpecs> { + unsafe fn service_interrupt(&self, interrupt: u32) -> bool { + match interrupt { + nvic::USART1 => self.usart1.handle_interrupt(), + nvic::USART2 => self.usart2.handle_interrupt(), + nvic::USART3 => self.usart3.handle_interrupt(), + nvic::EXTI0 => self.exti.handle_interrupt(), + nvic::EXTI1 => self.exti.handle_interrupt(), + nvic::EXTI2 => self.exti.handle_interrupt(), + nvic::EXTI3 => self.exti.handle_interrupt(), + nvic::EXTI4 => self.exti.handle_interrupt(), + nvic::EXTI9_5 => self.exti.handle_interrupt(), + nvic::EXTI15_10 => self.exti.handle_interrupt(), + + _ => return false, + } + true + } +} + +impl<'a, I: InterruptService + 'a> Stm32l4xx<'a, I> { + pub unsafe fn new(interrupt_service: &'a I) -> Self { + Self { + mpu: cortexm4f::mpu::new(), + userspace_kernel_boundary: cortexm4f::syscall::SysCall::new(), + interrupt_service, + } + } +} + +impl<'a, I: InterruptService + 'a> Chip for Stm32l4xx<'a, I> { + type MPU = cortexm4f::mpu::MPU; + type UserspaceKernelBoundary = cortexm4f::syscall::SysCall; + type ThreadIdProvider = cortexm4f::thread_id::CortexMThreadIdProvider; + + fn service_pending_interrupts(&self) { + unsafe { + while let Some(interrupt) = cortexm4f::nvic::next_pending() { + if !self.interrupt_service.service_interrupt(interrupt) { + panic!("unhandled interrupt {}", interrupt); + } + + let n = cortexm4f::nvic::Nvic::new(interrupt); + n.clear_pending(); + n.enable(); + } + } + } + + fn has_pending_interrupts(&self) -> bool { + unsafe { cortexm4f::nvic::has_pending() } + } + + fn mpu(&self) -> &cortexm4f::mpu::MPU { + &self.mpu + } + + fn userspace_kernel_boundary(&self) -> &cortexm4f::syscall::SysCall { + &self.userspace_kernel_boundary + } + + fn sleep(&self) { + unsafe { + cortexm4f::scb::unset_sleepdeep(); + cortexm4f::support::wfi(); + } + } + + unsafe fn with_interrupts_disabled(&self, f: F) -> R + where + F: FnOnce() -> R, + { + cortexm4f::support::with_interrupts_disabled(f) + } + + unsafe fn print_state(_this: Option<&Self>, write: &mut dyn Write) { + CortexM4F::print_cortexm_state(write); + } +} diff --git a/chips/stm32l4xx/src/chip_specific/chip_specs.rs b/chips/stm32l4xx/src/chip_specific/chip_specs.rs new file mode 100644 index 0000000000..b271cbc4df --- /dev/null +++ b/chips/stm32l4xx/src/chip_specific/chip_specs.rs @@ -0,0 +1,14 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +//! Trait that encompasses chip specifications +//! +//! The main use of this trait is to be passed as a bound for the type parameter for chip +//! peripherals in crates such as `stm32l476rg`. + +use crate::chip_specific::clock_constants::ClockConstants; +use crate::chip_specific::flash::FlashChipSpecific; +pub trait ChipSpecs: ClockConstants + FlashChipSpecific {} + +impl ChipSpecs for T {} diff --git a/chips/stm32l4xx/src/chip_specific/clock_constants.rs b/chips/stm32l4xx/src/chip_specific/clock_constants.rs new file mode 100644 index 0000000000..05c2b76f42 --- /dev/null +++ b/chips/stm32l4xx/src/chip_specific/clock_constants.rs @@ -0,0 +1,29 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +//! Clock-related constants for a particular chip + +/// PLL-related constants for specific for a specific chip +pub trait PllConstants { + /// PLL minimum frequency in MHz + const MIN_FREQ_MHZ: usize = 8; + /// PLL maximum frequency in MHz + // All boards support PLL frequencies up to 80MHz + const MAX_FREQ_MHZ: usize = 80; +} + +/// Generic clock constants for a specific chip +pub trait SystemClockConstants { + /// Maximum allowed APB1 frequency in MHz + const APB1_FREQUENCY_LIMIT_MHZ: usize = 80; + /// Maximum allowed APB2 frequency in MHz + const APB2_FREQUENCY_LIMIT_MHZ: usize = 80; + /// Maximum allowed system clock frequency in MHz + const SYS_CLOCK_FREQUENCY_LIMIT_MHZ: usize = 80; +} + +/// Clock constants for a specific chip +pub trait ClockConstants: SystemClockConstants + PllConstants {} + +impl ClockConstants for T {} diff --git a/chips/stm32l4xx/src/chip_specific/flash.rs b/chips/stm32l4xx/src/chip_specific/flash.rs new file mode 100644 index 0000000000..962cc02ef2 --- /dev/null +++ b/chips/stm32l4xx/src/chip_specific/flash.rs @@ -0,0 +1,51 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +//! Chip-specific flash code + +use core::fmt::Debug; + +pub trait FlashChipSpecific { + type FlashLatency: RegisterToFlashLatency + Clone + Copy + PartialEq + Debug + Into; + + // The number of wait cycles depends on two factors: system clock frequency and the supply + // voltage. + fn get_number_wait_cycles_based_on_frequency_and_voltage( + frequency_mhz: usize, + vos: usize, + ) -> Self::FlashLatency; +} + +pub trait RegisterToFlashLatency { + fn convert_register_to_enum(flash_latency_register: u32) -> Self; +} + +#[derive(Copy, Clone, PartialEq, Debug)] +pub enum FlashLatency5 { + Latency0, + Latency1, + Latency2, + Latency3, + Latency4, + Latency5, +} + +impl RegisterToFlashLatency for FlashLatency5 { + fn convert_register_to_enum(flash_latency_register: u32) -> Self { + match flash_latency_register { + 0 => Self::Latency0, + 1 => Self::Latency1, + 2 => Self::Latency2, + 3 => Self::Latency3, + 4 => Self::Latency4, + _ => Self::Latency5, + } + } +} + +impl From for u32 { + fn from(val: FlashLatency5) -> Self { + val as u32 + } +} diff --git a/chips/stm32l4xx/src/chip_specific/mod.rs b/chips/stm32l4xx/src/chip_specific/mod.rs new file mode 100644 index 0000000000..c450edf716 --- /dev/null +++ b/chips/stm32l4xx/src/chip_specific/mod.rs @@ -0,0 +1,14 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +//! This module contains all chip-specific code. +//! +//! Some models in the STM32L4 family may have additional features, while others not. Or they can +//! operate internally in different ways for the same feature. This module provides all the +//! chip-specific types and traits to be used by others modules in this crate or by other crates. + +pub mod chip_specs; +pub mod clock_constants; +pub mod flash; +pub use chip_specs::ChipSpecs; diff --git a/chips/stm32l4xx/src/clocks/clocks.rs b/chips/stm32l4xx/src/clocks/clocks.rs new file mode 100644 index 0000000000..1d135cae01 --- /dev/null +++ b/chips/stm32l4xx/src/clocks/clocks.rs @@ -0,0 +1,321 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +use kernel::utilities::cells::OptionalCell; +use kernel::ErrorCode; + +use crate::chip_specific::ChipSpecs as ChipSpecsTrait; +use crate::clocks::hsi::Hsi; +use crate::clocks::msi::Msi; +use crate::clocks::pll::Pll; +use crate::flash::Flash; +use crate::rcc::{AHBPrescaler, APBPrescaler, PllSource, Rcc, SysClockSource}; + +/// Main struct for configuring on-board clocks. +pub struct Clocks<'a, ChipSpecs> { + rcc: &'a Rcc, + flash: OptionalCell<&'a Flash>, + /// MSI (multispeed internal) RC oscillator clock + pub msi: Msi<'a>, + /// High speed internal clock + pub hsi: Hsi<'a>, + /// Main phase loop-lock clock + pub pll: Pll<'a, ChipSpecs>, +} + +impl<'a, ChipSpecs: ChipSpecsTrait> Clocks<'a, ChipSpecs> { + // The constructor must be called when the default peripherals are created + pub fn new(rcc: &'a Rcc) -> Self { + Self { + rcc, + flash: OptionalCell::empty(), + msi: Msi::new(rcc), + hsi: Hsi::new(rcc), + pll: Pll::new(rcc), + } + } + + // This method should be called when the dependencies are resolved + pub(crate) fn set_flash(&self, flash: &'a Flash) { + self.flash.set(flash); + } + + /// Set the AHB prescaler + /// + /// AHB bus, core, memory, DMA, Cortex System timer and FCLK Cortex free-running clock + /// frequencies are equal to the system clock frequency divided by the AHB prescaler. + /// + /// # Errors: + /// + /// + [Err]\([ErrorCode::FAIL]\) if changing the AHB prescaler doesn't preserve APB frequency + /// constraints + /// + [Err]\([ErrorCode::BUSY]\) if changing the AHB prescaler took too long. Retry. + pub fn set_ahb_prescaler(&self, prescaler: AHBPrescaler) -> Result<(), ErrorCode> { + // Changing the AHB prescaler affects the APB frequencies. A check must be done to ensure + // that the constraints are still valid + let divider: usize = prescaler.into(); + let new_ahb_frequency = self.get_sys_clock_frequency_mhz() / divider; + if !self.check_apb1_frequency_limit(new_ahb_frequency) + || !self.check_apb2_frequency_limit(new_ahb_frequency) + { + return Err(ErrorCode::FAIL); + } + + self.rcc.set_ahb_prescaler(prescaler); + + for _ in 0..16 { + if self.get_ahb_prescaler() == prescaler { + return Ok(()); + } + } + + Err(ErrorCode::BUSY) + } + + /// Get the current configured AHB prescaler + pub fn get_ahb_prescaler(&self) -> AHBPrescaler { + self.rcc.get_ahb_prescaler() + } + + /// Get the frequency of the AHB + pub fn get_ahb_frequency_mhz(&self) -> usize { + let ahb_divider: usize = self.get_ahb_prescaler().into(); + self.get_sys_clock_frequency_mhz() / ahb_divider + } + + // APB1 frequency must not be higher than the maximum allowable frequency. This method is + // called when the system clock source is changed. The ahb_frequency_mhz is the + // hypothetical future frequency. + fn check_apb1_frequency_limit(&self, ahb_frequency_mhz: usize) -> bool { + ahb_frequency_mhz + <= ChipSpecs::APB1_FREQUENCY_LIMIT_MHZ + * Into::::into(self.rcc.get_apb1_prescaler()) + } + + /// Set the APB1 prescaler. + /// + /// The APB1 peripheral clock frequency is equal to the AHB frequency divided by the APB1 + /// prescaler. + /// + /// # Errors: + /// + /// + [Err]\([ErrorCode::FAIL]\) if the desired prescaler would break the APB1 frequency limit + /// + [Err]\([ErrorCode::BUSY]\) if setting the prescaler took too long. Retry. + pub fn set_apb1_prescaler(&self, prescaler: APBPrescaler) -> Result<(), ErrorCode> { + let ahb_frequency = self.get_ahb_frequency_mhz(); + let divider: usize = prescaler.into(); + if ahb_frequency / divider > ChipSpecs::APB1_FREQUENCY_LIMIT_MHZ { + return Err(ErrorCode::FAIL); + } + + self.rcc.set_apb1_prescaler(prescaler); + + for _ in 0..16 { + if self.rcc.get_apb1_prescaler() == prescaler { + return Ok(()); + } + } + + Err(ErrorCode::BUSY) + } + + /// Get the current configured APB1 prescaler + pub fn get_apb1_prescaler(&self) -> APBPrescaler { + self.rcc.get_apb1_prescaler() + } + + /// Get the current APB1 frequency + pub fn get_apb1_frequency_mhz(&self) -> usize { + // Every enum variant can be converted into a usize + let divider: usize = self.rcc.get_apb1_prescaler().into(); + self.get_ahb_frequency_mhz() / divider + } + + // Same as for APB1, APB2 has a frequency limit that must be enforced by software + fn check_apb2_frequency_limit(&self, ahb_frequency_mhz: usize) -> bool { + ahb_frequency_mhz + <= ChipSpecs::APB2_FREQUENCY_LIMIT_MHZ + * Into::::into(self.rcc.get_apb2_prescaler()) + } + + /// Set the APB2 prescaler. + /// + /// The APB2 peripheral clock frequency is equal to the AHB frequency divided by the APB2 + /// prescaler. + /// + /// # Errors: + /// + /// + [Err]\([ErrorCode::FAIL]\) if the desired prescaler would break the APB2 frequency limit + /// + [Err]\([ErrorCode::BUSY]\) if setting the prescaler took too long. Retry. + pub fn set_apb2_prescaler(&self, prescaler: APBPrescaler) -> Result<(), ErrorCode> { + let current_ahb_frequency = self.get_ahb_frequency_mhz(); + let divider: usize = prescaler.into(); + if current_ahb_frequency / divider > ChipSpecs::APB2_FREQUENCY_LIMIT_MHZ { + return Err(ErrorCode::FAIL); + } + + self.rcc.set_apb2_prescaler(prescaler); + + for _ in 0..16 { + if self.rcc.get_apb2_prescaler() == prescaler { + return Ok(()); + } + } + + Err(ErrorCode::BUSY) + } + + /// Get the current configured APB2 prescaler + pub fn get_apb2_prescaler(&self) -> APBPrescaler { + self.rcc.get_apb2_prescaler() + } + + /// Get the current APB2 frequency + pub fn get_apb2_frequency_mhz(&self) -> usize { + // Every enum variant can be converted into a usize + let divider: usize = self.rcc.get_apb2_prescaler().into(); + self.get_ahb_frequency_mhz() / divider + } + + /// Set the system clock source + /// + /// # Errors: + /// + /// + [Err]\([ErrorCode::FAIL]\) if the source is not enabled. + /// + [Err]\([ErrorCode::SIZE]\) if the source frequency surpasses the system clock frequency + /// limit, or the APB1 and APB2 limits are not satisfied. + /// + [Err]\([ErrorCode::BUSY]\) if the source switching took too long. Retry. + pub fn set_sys_clock_source(&self, source: SysClockSource) -> Result<(), ErrorCode> { + // Immediately return if the required source is already configured as the system clock + // source. Should this maybe be Err(ErrorCode::ALREADY)? + if source == self.get_sys_clock_source() { + return Ok(()); + } + + // Ensure the source is enabled before configuring it as the system clock source + if !(match source { + SysClockSource::MSI => self.msi.is_enabled(), + SysClockSource::HSI => self.hsi.is_enabled(), + SysClockSource::PLL => self.pll.is_enabled(), + }) { + return Err(ErrorCode::FAIL); + } + + let current_frequency = self.get_sys_clock_frequency_mhz(); + + // Get the frequency of the source to be configured + let alternate_frequency = match source { + // The unwrap can't fail because the source clock status was checked before + SysClockSource::MSI => self.msi.get_frequency_mhz().unwrap(), + SysClockSource::HSI => self.hsi.get_frequency_mhz().unwrap(), + SysClockSource::PLL => self.pll.get_frequency_mhz().unwrap(), + }; + + // Check the alternate frequency is not higher than the system clock limit + if alternate_frequency > ChipSpecs::SYS_CLOCK_FREQUENCY_LIMIT_MHZ { + return Err(ErrorCode::SIZE); + } + + // Retrieve the currently configured AHB prescaler + let ahb_divider: usize = self.get_ahb_prescaler().into(); + // Compute the possible future AHB frequency + let ahb_frequency = alternate_frequency / ahb_divider; + + // APB1 frequency must not exceed APB1_FREQUENCY_LIMIT_MHZ + if !self.check_apb1_frequency_limit(ahb_frequency) { + return Err(ErrorCode::SIZE); + } + + // APB2 frequency must not exceed APB2_FREQUENCY_LIMIT_MHZ + if !self.check_apb2_frequency_limit(ahb_frequency) { + return Err(ErrorCode::SIZE); + } + + // The documentation recommends the following sequence when changing the system clock + // frequency: + // + // + if the desired frequency is higher than the current frequency, first change flash + // latency, then set the new system clock source. + // + if the desired frequency is lower than the current frequency, first change the system + // clock source, then set the flash latency + if alternate_frequency > current_frequency { + self.flash + .unwrap_or_panic() + .set_latency(alternate_frequency)?; + } + self.rcc.set_sys_clock_source(source); + if alternate_frequency < current_frequency { + self.flash + .unwrap_or_panic() + .set_latency(alternate_frequency)?; + } + + // If this point is reached, everything worked as expected + Ok(()) + } + + /// Get the current system clock source + pub fn get_sys_clock_source(&self) -> SysClockSource { + self.rcc.get_sys_clock_source() + } + + /// Get the current system clock frequency in MHz + pub fn get_sys_clock_frequency_mhz(&self) -> usize { + match self.get_sys_clock_source() { + SysClockSource::MSI => self.msi.get_frequency_mhz().unwrap(), + SysClockSource::HSI => self.hsi.get_frequency_mhz().unwrap(), + SysClockSource::PLL => self.pll.get_frequency_mhz().unwrap(), + } + } + + /// Set the frequency of the PLL clock. + /// + /// # Parameters + /// + /// + pll_source: PLL source clock (MSI or HSI) + /// + /// + desired_frequency_mhz: the desired frequency in MHz. Supported values: 8 - 80 MHz + /// + /// # Errors + /// + /// + [Err]\([ErrorCode::INVAL]\): if the desired frequency can't be achieved + /// + [Err]\([ErrorCode::FAIL]\): if the PLL clock is already enabled. It must be disabled before + pub fn set_pll_frequency_mhz( + &self, + pll_source: PllSource, + desired_frequency_mhz: usize, + ) -> Result<(), ErrorCode> { + let source_frequency = match pll_source { + PllSource::MSI => self.msi.get_frequency_mhz().unwrap(), + PllSource::HSI => self.hsi.get_frequency_mhz().unwrap(), + PllSource::NoClock => todo!(), + }; + self.pll + .set_frequency_mhz(pll_source, source_frequency, desired_frequency_mhz) + } +} + +/// Stm32l4Clocks trait +/// +/// This can be used to control clocks without the need to keep a reference of the chip specific +/// Clocks struct, for instance by peripherals +pub trait Stm32l4Clocks { + /// Get RCC instance + fn get_rcc(&self) -> &Rcc; + + /// Get current AHB clock (HCLK) frequency in Hz + fn get_ahb_frequency(&self) -> usize; + + // Extend this to expose additional clock resources +} + +impl<'a, ChipSpecs: ChipSpecsTrait> Stm32l4Clocks for Clocks<'a, ChipSpecs> { + fn get_rcc(&self) -> &'a Rcc { + self.rcc + } + + fn get_ahb_frequency(&self) -> usize { + self.get_ahb_frequency_mhz() * 1_000_000 + } +} diff --git a/chips/stm32l4xx/src/clocks/hsi.rs b/chips/stm32l4xx/src/clocks/hsi.rs new file mode 100644 index 0000000000..f36e56bd16 --- /dev/null +++ b/chips/stm32l4xx/src/clocks/hsi.rs @@ -0,0 +1,96 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +use crate::rcc::Rcc; + +use kernel::ErrorCode; + +/// HSI frequency in MHz +pub const HSI_FREQUENCY_MHZ: usize = 16; + +/// Main HSI clock structure +pub struct Hsi<'a> { + rcc: &'a Rcc, +} + +impl<'a> Hsi<'a> { + /// Create a new instance of the HSI clock. + /// + /// # Parameters + /// + /// + rcc: an instance of [crate::rcc] + /// + /// # Returns + /// + /// An instance of the HSI clock. + pub(in crate::clocks) fn new(rcc: &'a Rcc) -> Self { + Self { rcc } + } + + /// Start the HSI clock. + /// + /// # Errors + /// + /// + [Err]\([ErrorCode::BUSY]\): if enabling the HSI clock took too long. Recall this method to + /// ensure the HSI clock is running. + pub fn enable(&self) -> Result<(), ErrorCode> { + self.rcc.enable_hsi_clock(); + + for _ in 0..100 { + if self.rcc.is_ready_hsi_clock() { + return Ok(()); + } + } + + Err(ErrorCode::BUSY) + } + + /// Stop the HSI clock. + /// + /// # Errors + /// + /// + [Err]\([ErrorCode::FAIL]\): if the HSI clock is configured as the system clock. + /// + [Err]\([ErrorCode::BUSY]\): disabling the HSI clock took to long. Retry to ensure it is + /// not running. + pub fn disable(&self) -> Result<(), ErrorCode> { + if self.rcc.is_hsi_clock_system_clock() { + return Err(ErrorCode::FAIL); + } + + self.rcc.disable_hsi_clock(); + + for _ in 0..10 { + if !self.rcc.is_ready_hsi_clock() { + return Ok(()); + } + } + + Err(ErrorCode::BUSY) + } + + /// Check whether the HSI clock is enabled or not. + /// + /// # Returns + /// + /// + [false]: the HSI clock is not enabled + /// + [true]: the HSI clock is enabled + pub fn is_enabled(&self) -> bool { + self.rcc.is_enabled_hsi_clock() + } + + /// Get the frequency in MHz of the HSI clock. + /// + /// # Returns + /// + /// + [Some]\(frequency_mhz\): if the HSI clock is enabled. + /// + [None]: if the HSI clock is disabled. + pub fn get_frequency_mhz(&self) -> Option { + if self.is_enabled() { + Some(HSI_FREQUENCY_MHZ) + } else { + None + } + } +} + diff --git a/chips/stm32l4xx/src/clocks/mod.rs b/chips/stm32l4xx/src/clocks/mod.rs new file mode 100644 index 0000000000..184981720d --- /dev/null +++ b/chips/stm32l4xx/src/clocks/mod.rs @@ -0,0 +1,10 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +pub mod clocks; +pub mod hsi; +pub mod msi; +pub mod phclk; +pub mod pll; +pub use crate::clocks::clocks::{Clocks, Stm32l4Clocks}; diff --git a/chips/stm32l4xx/src/clocks/msi.rs b/chips/stm32l4xx/src/clocks/msi.rs new file mode 100644 index 0000000000..6d22ce87e7 --- /dev/null +++ b/chips/stm32l4xx/src/clocks/msi.rs @@ -0,0 +1,149 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +use crate::rcc::Rcc; + +use kernel::ErrorCode; + +/// MSI frequency in MHz +pub const MSI_FREQUENCY_MHZ: usize = 4; + +/// Main MSI clock structure +pub struct Msi<'a> { + rcc: &'a Rcc, +} + +impl<'a> Msi<'a> { + /// Create a new instance of the MSI clock. + /// + /// # Parameters + /// + /// + rcc: an instance of [crate::rcc] + /// + /// # Returns + /// + /// An instance of the MSI clock. + pub(in crate::clocks) fn new(rcc: &'a Rcc) -> Self { + Self { rcc } + } + + /// Start the MSI clock. + /// + /// # Errors + /// + /// + [Err]\([ErrorCode::BUSY]\): if enabling the MSI clock took too long. Recall this method to + /// ensure the MSI clock is running. + pub fn enable(&self) -> Result<(), ErrorCode> { + self.rcc.enable_msi_clock(); + + for _ in 0..100 { + if self.rcc.is_ready_msi_clock() { + return Ok(()); + } + } + + Err(ErrorCode::BUSY) + } + + /// Stop the MSI clock. + /// + /// # Errors + /// + /// + [Err]\([ErrorCode::FAIL]\): if the MSI clock is configured as the system clock. + /// + [Err]\([ErrorCode::BUSY]\): disabling the MSI clock took to long. Retry to ensure it is + /// not running. + pub fn disable(&self) -> Result<(), ErrorCode> { + if self.rcc.is_msi_clock_system_clock() { + return Err(ErrorCode::FAIL); + } + + self.rcc.disable_msi_clock(); + + for _ in 0..10 { + if !self.rcc.is_ready_msi_clock() { + return Ok(()); + } + } + + Err(ErrorCode::BUSY) + } + + /// Check whether the MSI clock is enabled or not. + /// + /// # Returns + /// + /// + [false]: the MSI clock is not enabled + /// + [true]: the MSI clock is enabled + pub fn is_enabled(&self) -> bool { + self.rcc.is_enabled_msi_clock() + } + + /// Get the frequency in MHz of the MSI clock. + /// + /// # Returns + /// + /// + [Some]\(frequency_mhz\): if the MSI clock is enabled. + /// + [None]: if the MSI clock is disabled. + pub fn get_frequency_mhz(&self) -> Option { + if self.is_enabled() { + Some(MSI_FREQUENCY_MHZ) + } else { + None + } + } +} + +/// Tests for the MSI clock +/// +/// This module ensures that the MSI clock works as expected. If changes are brought to the MSI +/// clock, ensure to run all the tests to see if anything is broken. +/// +/// # Usage +/// +/// First, import the [crate::clocks::msi] module in the desired board main file: +/// +/// ```rust,ignore +/// use stm32l476rg::clocks::msi; +/// ``` +/// +/// Then, to run the tests, put the following line before [kernel::process::load_processes]: +/// +/// ```rust,ignore +/// msi::tests::run(&peripherals.stm32l4.clocks.msi); +/// ``` +/// +/// If everything works as expected, the following message should be printed on the kernel console: +/// +/// ```text +/// =============================================== +/// Testing MSI... +/// Finished testing MSI. Everything is alright! +/// =============================================== +/// ``` +/// +/// **NOTE:** All these tests assume default boot configuration. +pub mod tests { + use super::{ErrorCode, Msi, MSI_FREQUENCY_MHZ}; + use kernel::debug; + + /// Run the entire test suite. + pub fn run(msi: &Msi) { + debug!(""); + debug!("==============================================="); + debug!("Testing MSI..."); + + // By default, the MSI clock is enabled + assert!(msi.is_enabled()); + + // MSI frequency is 4MHz + assert_eq!(Some(MSI_FREQUENCY_MHZ), msi.get_frequency_mhz()); + + // MSI is used as system clock, so disable should fail + assert_eq!(Err(ErrorCode::FAIL), msi.disable()); + + debug!("Finished testing MSI. Everything is alright!"); + debug!("==============================================="); + debug!(""); + } +} diff --git a/chips/stm32l4xx/src/clocks/phclk.rs b/chips/stm32l4xx/src/clocks/phclk.rs new file mode 100644 index 0000000000..42112b5191 --- /dev/null +++ b/chips/stm32l4xx/src/clocks/phclk.rs @@ -0,0 +1,213 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +use crate::clocks::Stm32l4Clocks; +use kernel::platform::chip::ClockInterface; + +pub struct PeripheralClock<'a> { + pub clock: PeripheralClockType, + clocks: &'a dyn Stm32l4Clocks, +} + +/// Bus + Clock name for the peripherals +pub enum PeripheralClockType { + AHB1(HCLK1), + AHB2(HCLK2), + APB1(PCLK1), + APB2(PCLK2), +} + +/// Peripherals clocked by HCLK1 +pub enum HCLK1 { + DMA1, + DMA2, +} + +/// Peripherals clocked by HCLK2 +pub enum HCLK2 { + GPIOH, + GPIOG, + GPIOF, + GPIOE, + GPIOD, + GPIOC, + GPIOB, + GPIOA, +} + +/// Peripherals clocked by PCLK1 +pub enum PCLK1 { + USART2, + USART3, +} + +/// Peripherals clocked by PCLK2 +pub enum PCLK2 { + SYSCFG, + USART1, +} + +impl<'a> PeripheralClock<'a> { + pub const fn new(clock: PeripheralClockType, clocks: &'a dyn Stm32l4Clocks) -> Self { + Self { clock, clocks } + } + + pub fn get_frequency(&self) -> u32 { + let rcc = self.clocks.get_rcc(); + let hclk_freq = self.clocks.get_ahb_frequency(); + match self.clock { + PeripheralClockType::AHB1(_) | PeripheralClockType::AHB2(_) => hclk_freq as u32, + PeripheralClockType::APB1(_) => { + let prescaler = rcc.get_apb1_prescaler(); + (hclk_freq / usize::from(prescaler)) as u32 + } + PeripheralClockType::APB2(_) => { + let prescaler = rcc.get_apb2_prescaler(); + (hclk_freq / usize::from(prescaler)) as u32 + } + } + } +} + +impl ClockInterface for PeripheralClock<'_> { + fn is_enabled(&self) -> bool { + let rcc = self.clocks.get_rcc(); + match self.clock { + PeripheralClockType::AHB1(ref v) => match v { + HCLK1::DMA1 => rcc.is_enabled_dma1_clock(), + HCLK1::DMA2 => rcc.is_enabled_dma2_clock(), + }, + PeripheralClockType::AHB2(ref v) => match v { + HCLK2::GPIOH => rcc.is_enabled_gpioh_clock(), + HCLK2::GPIOG => rcc.is_enabled_gpiog_clock(), + HCLK2::GPIOF => rcc.is_enabled_gpiof_clock(), + HCLK2::GPIOE => rcc.is_enabled_gpioe_clock(), + HCLK2::GPIOD => rcc.is_enabled_gpiod_clock(), + HCLK2::GPIOC => rcc.is_enabled_gpioc_clock(), + HCLK2::GPIOB => rcc.is_enabled_gpiob_clock(), + HCLK2::GPIOA => rcc.is_enabled_gpioa_clock(), + }, + PeripheralClockType::APB1(ref v) => match v { + PCLK1::USART2 => rcc.is_enabled_usart2_clock(), + PCLK1::USART3 => rcc.is_enabled_usart3_clock(), + }, + PeripheralClockType::APB2(ref v) => match v { + PCLK2::SYSCFG => rcc.is_enabled_syscfg_clock(), + PCLK2::USART1 => rcc.is_enabled_usart1_clock(), + }, + } + } + + fn enable(&self) { + let rcc = self.clocks.get_rcc(); + match self.clock { + PeripheralClockType::AHB1(ref v) => match v { + HCLK1::DMA1 => { + rcc.enable_dma1_clock(); + } + HCLK1::DMA2 => { + rcc.enable_dma2_clock(); + } + }, + PeripheralClockType::AHB2(ref v) => match v { + HCLK2::GPIOH => { + rcc.enable_gpioh_clock(); + } + HCLK2::GPIOG => { + rcc.enable_gpiog_clock(); + } + HCLK2::GPIOF => { + rcc.enable_gpiof_clock(); + } + HCLK2::GPIOE => { + rcc.enable_gpioe_clock(); + } + HCLK2::GPIOD => { + rcc.enable_gpiod_clock(); + } + HCLK2::GPIOC => { + rcc.enable_gpioc_clock(); + } + HCLK2::GPIOB => { + rcc.enable_gpiob_clock(); + } + HCLK2::GPIOA => { + rcc.enable_gpioa_clock(); + } + }, + PeripheralClockType::APB1(ref v) => match v { + PCLK1::USART2 => { + rcc.enable_usart2_clock(); + } + PCLK1::USART3 => { + rcc.enable_usart3_clock(); + } + }, + PeripheralClockType::APB2(ref v) => match v { + PCLK2::SYSCFG => { + rcc.enable_syscfg_clock(); + } + PCLK2::USART1 => { + rcc.enable_usart1_clock(); + } + }, + } + } + + fn disable(&self) { + let rcc = self.clocks.get_rcc(); + match self.clock { + PeripheralClockType::AHB1(ref v) => match v { + HCLK1::DMA1 => { + rcc.disable_dma1_clock(); + } + HCLK1::DMA2 => { + rcc.disable_dma2_clock(); + } + }, + PeripheralClockType::AHB2(ref v) => match v { + HCLK2::GPIOH => { + rcc.disable_gpioh_clock(); + } + HCLK2::GPIOG => { + rcc.disable_gpiog_clock(); + } + HCLK2::GPIOF => { + rcc.disable_gpiof_clock(); + } + HCLK2::GPIOE => { + rcc.disable_gpioe_clock(); + } + HCLK2::GPIOD => { + rcc.disable_gpiod_clock(); + } + HCLK2::GPIOC => { + rcc.disable_gpioc_clock(); + } + HCLK2::GPIOB => { + rcc.disable_gpiob_clock(); + } + HCLK2::GPIOA => { + rcc.disable_gpioa_clock(); + } + }, + PeripheralClockType::APB1(ref v) => match v { + PCLK1::USART2 => { + rcc.disable_usart2_clock(); + } + PCLK1::USART3 => { + rcc.disable_usart3_clock(); + } + }, + PeripheralClockType::APB2(ref v) => match v { + PCLK2::SYSCFG => { + rcc.disable_syscfg_clock(); + } + PCLK2::USART1 => { + rcc.disable_usart1_clock(); + } + }, + } + } +} diff --git a/chips/stm32l4xx/src/clocks/pll.rs b/chips/stm32l4xx/src/clocks/pll.rs new file mode 100644 index 0000000000..a0e7ff4cac --- /dev/null +++ b/chips/stm32l4xx/src/clocks/pll.rs @@ -0,0 +1,241 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +use crate::chip_specific::clock_constants; +use crate::clocks::msi::MSI_FREQUENCY_MHZ; +use crate::rcc::PllSource; +use crate::rcc::Rcc; +use crate::rcc::SysClockSource; +use crate::rcc::{DEFAULT_PLLM_VALUE, DEFAULT_PLLN_VALUE, DEFAULT_PLLR_VALUE}; + +use kernel::utilities::cells::OptionalCell; +use kernel::ErrorCode; + +use core::marker::PhantomData; + +/// Main PLL clock structure. +pub struct Pll<'a, PllConstants> { + rcc: &'a Rcc, + frequency_mhz: OptionalCell, + _marker: PhantomData, +} + +impl<'a, PllConstants: clock_constants::PllConstants> Pll<'a, PllConstants> { + // Create a new instance of the PLL clock. + // + // The instance of the PLL clock is configured to run at 96MHz and with minimal PLL jitter + // effects. + // + // # Parameters + // + // + rcc: an instance of [crate::rcc] + // + // # Returns + // + // An instance of the PLL clock. + pub(in crate::clocks) fn new(rcc: &'a Rcc) -> Self { + let pllm: usize = Into::into(DEFAULT_PLLM_VALUE); + let pllr: usize = Into::into(DEFAULT_PLLR_VALUE); + Self { + rcc, + frequency_mhz: OptionalCell::new(MSI_FREQUENCY_MHZ / pllm * DEFAULT_PLLN_VALUE / pllr), + _marker: PhantomData, + } + } + + /// Set the PLL source clock + fn set_pll_source_clock(&self, source: PllSource) -> Result<(), ErrorCode> { + if self.is_enabled() { + Err(ErrorCode::FAIL) + } else { + self.rcc.set_pll_clock_source(source); + Ok(()) + } + } + + /// Start the PLL clock. + /// + /// # Errors + /// + /// + [Err]\([ErrorCode::FAIL]\): if enabling the PLL clock has set NoClock. First set pll clock source + /// + [Err]\([ErrorCode::BUSY]\): if enabling the PLL clock took too long. Recall this method to + /// ensure the PLL clock is running. + pub fn enable(&self) -> Result<(), ErrorCode> { + if self.rcc.get_pll_clock_source() == PllSource::NoClock { + return Err(ErrorCode::FAIL); + } + // Enable the PLL clock + self.rcc.enable_pll_clock(); + + // Wait until the PLL clock is locked. + // 200 was obtained by running tests in release mode + for _ in 0..200 { + if self.rcc.is_locked_pll_clock() { + return Ok(()); + } + } + + // If waiting for the PLL clock took too long, return ErrorCode::BUSY + Err(ErrorCode::BUSY) + } + + /// Stop the PLL clock. + /// + /// # Errors + /// + /// + [Err]\([ErrorCode::FAIL]\): if the PLL clock is configured as the system clock. + /// + [Err]\([ErrorCode::BUSY]\): disabling the PLL clock took to long. Retry to ensure it is + /// not running. + pub fn disable(&self) -> Result<(), ErrorCode> { + // Can't disable the PLL clock when it is used as the system clock + if self.rcc.get_sys_clock_source() == SysClockSource::PLL { + return Err(ErrorCode::FAIL); + } + + // Disable the PLL clock + self.rcc.disable_pll_clock(); + self.rcc.set_pll_clock_source(PllSource::NoClock); + + // Wait to unlock the PLL clock + // 10 was obtained by testing in release mode + for _ in 0..10 { + if !self.rcc.is_locked_pll_clock() { + return Ok(()); + } + } + + // If the waiting was too long, return ErrorCode::BUSY + Err(ErrorCode::BUSY) + } + + /// Check whether the PLL clock is enabled or not. + /// + /// # Returns + /// + /// + [false]: the PLL clock is not enabled + /// + [true]: the PLL clock is enabled + pub fn is_enabled(&self) -> bool { + self.rcc.is_enabled_pll_clock() + } + + /// Set the frequency of the PLL clock. + /// + /// Missing configuration for f_in_khz = 48000 target = 59 Mhz + /// Missing configuration for f_in_khz = 48000 target = 61 Mhz + /// Missing configuration for f_in_khz = 48000 target = 65 Mhz + /// Missing configuration for f_in_khz = 48000 target = 67 Mhz + /// Missing configuration for f_in_khz = 48000 target = 71 Mhz + /// Missing configuration for f_in_khz = 48000 target = 73 Mhz + /// Missing configuration for f_in_khz = 48000 target = 77 Mhz + /// Missing configuration for f_in_khz = 48000 target = 79 Mhz + /// + /// # Parameters + /// + /// + pll_source: PLL source clock (HSI or HSE) + /// + /// + source_frequency: the frequency of the PLL source clock in MHz. For the HSI the frequency + /// is fixed to 16MHz. For the HSE, the frequency is hardware-dependent + /// + /// + desired_frequency_mhz: the desired frequency in MHz. Supported values: 8 - 80 MHz + /// + /// # Errors + /// + /// + [Err]\([ErrorCode::INVAL]\): if the desired frequency can't be achieved + /// + [Err]\([ErrorCode::FAIL]\): if the PLL clock is already enabled. It must be disabled before + /// configuring it. + pub(super) fn set_frequency_mhz( + &self, + pll_source: PllSource, + source_frequency: usize, + desired_frequency_mhz: usize, + ) -> Result<(), ErrorCode> { + // Check for errors: + // + PLL clock running + // + invalid frequency + if self.rcc.is_enabled_pll_clock() { + return Err(ErrorCode::FAIL); + } else if desired_frequency_mhz < PllConstants::MIN_FREQ_MHZ + || desired_frequency_mhz > PllConstants::MAX_FREQ_MHZ + { + return Err(ErrorCode::INVAL); + } + + // The output frequencies for the PLL clock is computed as following: + // Source frequency / PLLM = VCO input frequency (must range from 4 MHz to 16 MHz) + // VCO output frequency = VCO input frequency * PLLN (must range from 64 MHz to 344 MHz) + // PLL output frequency = VCO output frequency / PLLR (must range from 8 Mhz to 80 Mhz) + + // Set PLL source (MSI or HSI) + if self.set_pll_source_clock(pll_source) != Ok(()) { + return Err(ErrorCode::FAIL); + } + + if source_frequency < 4000 { + return Err(ErrorCode::FAIL); + } + if let Some((m, n, r, _sysclk)) = Self::find_pll(source_frequency, desired_frequency_mhz) { + self.rcc.set_pll_clock_m_divider(m.into()); + self.rcc.set_pll_clock_n_multiplier(n); + self.rcc.set_pll_clock_r_divider(r.into()); + Ok(()) + } else { + return Err(ErrorCode::FAIL); + } + } + + fn find_pll(f_in_khz: usize, target_mhz: usize) -> Option<(usize, usize, usize, usize)> { + let target_khz = target_mhz * 1000; + + for m in 1..=8 { + let vco_in = f_in_khz / m; + if !(4_000..=16_000).contains(&vco_in) { + continue; + } + + for n in 8..=86 { + let vco_out = vco_in * n; + if !(64_000..=344_000).contains(&vco_out) { + continue; + } + + for &r in &[2, 4, 6, 8] { + // Sprawdź, czy vco_out dzieli się równo przez R + if vco_out % r != 0 { + continue; // SYSCLK nie byłby całkowity + } + + let sys = vco_out / r; + + if !(8_000..=80_000).contains(&sys) { + continue; + } + + let err = if sys > target_khz { + sys - target_khz + } else { + target_khz - sys + }; + + if err == 0 { + return Some((m, n, r, sys / 1000)); // w MHz + } + } + } + } + None + } + /// Get the frequency in MHz of the PLL clock. + /// + /// # Returns + /// + /// + [Some]\(frequency_mhz\): if the PLL clock is enabled. + /// + [None]: if the PLL clock is disabled. + pub fn get_frequency_mhz(&self) -> Option { + if self.is_enabled() { + self.frequency_mhz.get() + } else { + None + } + } +} diff --git a/chips/stm32l4xx/src/exti.rs b/chips/stm32l4xx/src/exti.rs new file mode 100644 index 0000000000..bcb2d4a80c --- /dev/null +++ b/chips/stm32l4xx/src/exti.rs @@ -0,0 +1,497 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +use cortexm4f::support::with_interrupts_disabled; +use enum_primitive::cast::FromPrimitive; +use enum_primitive::enum_from_primitive; +use kernel::platform::chip::ClockInterface; +use kernel::utilities::cells::OptionalCell; +use kernel::utilities::registers::interfaces::{ReadWriteable, Readable, Writeable}; +use kernel::utilities::registers::{register_bitfields, ReadWrite}; +use kernel::utilities::StaticRef; + +use crate::gpio; +use crate::syscfg; + +/// External interrupt/event controller (STM32L476) +/// Reference: RM0351, EXTI chapter. +#[repr(C)] +struct ExtiRegisters { + /// Interrupt mask register 1 (lines 0..31) + imr1: ReadWrite, + /// Event mask register 1 (lines 0..31) + emr1: ReadWrite, + /// Rising trigger selection register 1 (lines 0..31) + rtsr1: ReadWrite, + /// Falling trigger selection register 1 (lines 0..31) + ftsr1: ReadWrite, + /// Software interrupt event register 1 (lines 0..31) + swier1: ReadWrite, + /// Pending register 1 (lines 0..31) + pr1: ReadWrite, + /// Interrupt mask register 2 (higher lines) + imr2: ReadWrite, + /// Event mask register 2 (higher lines) + emr2: ReadWrite, + /// Rising trigger selection register 2 (higher lines) + rtsr2: ReadWrite, + /// Falling trigger selection register 2 (higher lines) + ftsr2: ReadWrite, + /// Software interrupt event register 2 (higher lines) + swier2: ReadWrite, + /// Pending register 2 (higher lines) + pr2: ReadWrite, +} + +register_bitfields![u32, + IMR1 [ + MR0 OFFSET(0) NUMBITS(1) [], + MR1 OFFSET(1) NUMBITS(1) [], + MR2 OFFSET(2) NUMBITS(1) [], + MR3 OFFSET(3) NUMBITS(1) [], + MR4 OFFSET(4) NUMBITS(1) [], + MR5 OFFSET(5) NUMBITS(1) [], + MR6 OFFSET(6) NUMBITS(1) [], + MR7 OFFSET(7) NUMBITS(1) [], + MR8 OFFSET(8) NUMBITS(1) [], + MR9 OFFSET(9) NUMBITS(1) [], + MR10 OFFSET(10) NUMBITS(1) [], + MR11 OFFSET(11) NUMBITS(1) [], + MR12 OFFSET(12) NUMBITS(1) [], + MR13 OFFSET(13) NUMBITS(1) [], + MR14 OFFSET(14) NUMBITS(1) [], + MR15 OFFSET(15) NUMBITS(1) [] + ], + EMR1 [ + MR0 OFFSET(0) NUMBITS(1) [], + MR1 OFFSET(1) NUMBITS(1) [], + MR2 OFFSET(2) NUMBITS(1) [], + MR3 OFFSET(3) NUMBITS(1) [], + MR4 OFFSET(4) NUMBITS(1) [], + MR5 OFFSET(5) NUMBITS(1) [], + MR6 OFFSET(6) NUMBITS(1) [], + MR7 OFFSET(7) NUMBITS(1) [], + MR8 OFFSET(8) NUMBITS(1) [], + MR9 OFFSET(9) NUMBITS(1) [], + MR10 OFFSET(10) NUMBITS(1) [], + MR11 OFFSET(11) NUMBITS(1) [], + MR12 OFFSET(12) NUMBITS(1) [], + MR13 OFFSET(13) NUMBITS(1) [], + MR14 OFFSET(14) NUMBITS(1) [], + MR15 OFFSET(15) NUMBITS(1) [] + ], + RTSR1 [ + TR0 OFFSET(0) NUMBITS(1) [], + TR1 OFFSET(1) NUMBITS(1) [], + TR2 OFFSET(2) NUMBITS(1) [], + TR3 OFFSET(3) NUMBITS(1) [], + TR4 OFFSET(4) NUMBITS(1) [], + TR5 OFFSET(5) NUMBITS(1) [], + TR6 OFFSET(6) NUMBITS(1) [], + TR7 OFFSET(7) NUMBITS(1) [], + TR8 OFFSET(8) NUMBITS(1) [], + TR9 OFFSET(9) NUMBITS(1) [], + TR10 OFFSET(10) NUMBITS(1) [], + TR11 OFFSET(11) NUMBITS(1) [], + TR12 OFFSET(12) NUMBITS(1) [], + TR13 OFFSET(13) NUMBITS(1) [], + TR14 OFFSET(14) NUMBITS(1) [], + TR15 OFFSET(15) NUMBITS(1) [] + ], + FTSR1 [ + TR0 OFFSET(0) NUMBITS(1) [], + TR1 OFFSET(1) NUMBITS(1) [], + TR2 OFFSET(2) NUMBITS(1) [], + TR3 OFFSET(3) NUMBITS(1) [], + TR4 OFFSET(4) NUMBITS(1) [], + TR5 OFFSET(5) NUMBITS(1) [], + TR6 OFFSET(6) NUMBITS(1) [], + TR7 OFFSET(7) NUMBITS(1) [], + TR8 OFFSET(8) NUMBITS(1) [], + TR9 OFFSET(9) NUMBITS(1) [], + TR10 OFFSET(10) NUMBITS(1) [], + TR11 OFFSET(11) NUMBITS(1) [], + TR12 OFFSET(12) NUMBITS(1) [], + TR13 OFFSET(13) NUMBITS(1) [], + TR14 OFFSET(14) NUMBITS(1) [], + TR15 OFFSET(15) NUMBITS(1) [] + ], + SWIER1 [ + SWIER0 OFFSET(0) NUMBITS(1) [], + SWIER1 OFFSET(1) NUMBITS(1) [], + SWIER2 OFFSET(2) NUMBITS(1) [], + SWIER3 OFFSET(3) NUMBITS(1) [], + SWIER4 OFFSET(4) NUMBITS(1) [], + SWIER5 OFFSET(5) NUMBITS(1) [], + SWIER6 OFFSET(6) NUMBITS(1) [], + SWIER7 OFFSET(7) NUMBITS(1) [], + SWIER8 OFFSET(8) NUMBITS(1) [], + SWIER9 OFFSET(9) NUMBITS(1) [], + SWIER10 OFFSET(10) NUMBITS(1) [], + SWIER11 OFFSET(11) NUMBITS(1) [], + SWIER12 OFFSET(12) NUMBITS(1) [], + SWIER13 OFFSET(13) NUMBITS(1) [], + SWIER14 OFFSET(14) NUMBITS(1) [], + SWIER15 OFFSET(15) NUMBITS(1) [] + ], + PR1 [ + PR0 OFFSET(0) NUMBITS(1) [], + PR1 OFFSET(1) NUMBITS(1) [], + PR2 OFFSET(2) NUMBITS(1) [], + PR3 OFFSET(3) NUMBITS(1) [], + PR4 OFFSET(4) NUMBITS(1) [], + PR5 OFFSET(5) NUMBITS(1) [], + PR6 OFFSET(6) NUMBITS(1) [], + PR7 OFFSET(7) NUMBITS(1) [], + PR8 OFFSET(8) NUMBITS(1) [], + PR9 OFFSET(9) NUMBITS(1) [], + PR10 OFFSET(10) NUMBITS(1) [], + PR11 OFFSET(11) NUMBITS(1) [], + PR12 OFFSET(12) NUMBITS(1) [], + PR13 OFFSET(13) NUMBITS(1) [], + PR14 OFFSET(14) NUMBITS(1) [], + PR15 OFFSET(15) NUMBITS(1) [] + ], + // Minimal higher-line registers placeholders (not actively used yet) + IMR2 [ MR32 OFFSET(0) NUMBITS(1) [] ], + EMR2 [ MR32 OFFSET(0) NUMBITS(1) [] ], + RTSR2 [ TR32 OFFSET(0) NUMBITS(1) [] ], + FTSR2 [ TR32 OFFSET(0) NUMBITS(1) [] ], + SWIER2 [ SWIER32 OFFSET(0) NUMBITS(1) [] ], + PR2 [ PR32 OFFSET(0) NUMBITS(1) [] ], +]; + +const EXTI_BASE: StaticRef = + unsafe { StaticRef::new(0x40010400 as *const ExtiRegisters) }; + +/// EXTI overview (STM32L476): +/// +/// External interrupt/event lines 0–15 correspond directly to the 16 GPIO pins +/// on a port. They are presented to the NVIC using a mix of dedicated and +/// grouped IRQs: +/// +/// - Lines 0,1,2,3,4 -> `EXTI0`..`EXTI4` (NVIC IRQs 6–10) +/// - Lines 5–9 -> grouped into `EXTI9_5` (NVIC IRQ 23) +/// - Lines 10–15 -> grouped into `EXTI15_10` (NVIC IRQ 40) +/// +/// Internal (non‑GPIO) EXTI lines above 15 (e.g. PVD/PVM, RTC events, USB, TAMP, +/// etc.) are routed to other dedicated NVIC IRQs (see `nvic.rs`) and are not +/// currently modelled in this driver; we restrict `LineId` to 0–15 for GPIO use. +/// +/// Pending bits are level sources: a set bit in PR1 keeps the NVIC IRQ asserted +/// until software writes 1 to clear it. The top‑half handler must therefore +/// acknowledge (clear) the source to avoid repeated interrupts. +/// +/// `EXTI_EVENTS` captures which GPIO line(s) were pending before they were +/// cleared, allowing deferred processing outside the immediate ISR if desired. +/// +/// Reference: RM0351, EXTI chapter (block diagram & register descriptions). +#[no_mangle] +#[used] +pub static mut EXTI_EVENTS: u32 = 0; + +enum_from_primitive! { + #[repr(u8)] + #[derive(Copy, Clone)] + pub enum LineId { + Exti0 = 0, + Exti1 = 1, + Exti2 = 2, + Exti3 = 3, + Exti4 = 4, + Exti5 = 5, + Exti6 = 6, + Exti7 = 7, + Exti8 = 8, + Exti9 = 9, + Exti10 = 10, + Exti11 = 11, + Exti12 = 12, + Exti13 = 13, + Exti14 = 14, + Exti15 = 15, + } +} + +// `line_gpiopin_map` is used to call `handle_interrupt()` on the pin. +pub struct Exti<'a> { + registers: StaticRef, + clock: ExtiClock<'a>, + line_gpiopin_map: [OptionalCell<&'static gpio::Pin<'static>>; 16], + syscfg: &'a syscfg::Syscfg<'a>, +} + +impl<'a> Exti<'a> { + pub const fn new(syscfg: &'a syscfg::Syscfg<'a>) -> Self { + Self { + registers: EXTI_BASE, + clock: ExtiClock(syscfg), + line_gpiopin_map: [ + OptionalCell::empty(), + OptionalCell::empty(), + OptionalCell::empty(), + OptionalCell::empty(), + OptionalCell::empty(), + OptionalCell::empty(), + OptionalCell::empty(), + OptionalCell::empty(), + OptionalCell::empty(), + OptionalCell::empty(), + OptionalCell::empty(), + OptionalCell::empty(), + OptionalCell::empty(), + OptionalCell::empty(), + OptionalCell::empty(), + OptionalCell::empty(), + ], + syscfg, + } + } + + pub fn is_enabled_clock(&self) -> bool { + self.clock.is_enabled() + } + + pub fn enable_clock(&self) { + self.clock.enable(); + } + + pub fn disable_clock(&self) { + self.clock.disable(); + } + + pub fn associate_line_gpiopin(&self, lineid: LineId, pin: &'static gpio::Pin<'static>) { + self.line_gpiopin_map[usize::from(lineid as u8)].set(pin); + self.syscfg.configure_interrupt(pin.get_pinid()); + pin.set_exti_lineid(lineid); + + // By default, all interrupts are masked. But, this will ensure that it + // is really the case. + self.mask_interrupt(lineid); + } + + pub fn mask_interrupt(&self, lineid: LineId) { + match lineid { + LineId::Exti0 => self.registers.imr1.modify(IMR1::MR0::CLEAR), + LineId::Exti1 => self.registers.imr1.modify(IMR1::MR1::CLEAR), + LineId::Exti2 => self.registers.imr1.modify(IMR1::MR2::CLEAR), + LineId::Exti3 => self.registers.imr1.modify(IMR1::MR3::CLEAR), + LineId::Exti4 => self.registers.imr1.modify(IMR1::MR4::CLEAR), + LineId::Exti5 => self.registers.imr1.modify(IMR1::MR5::CLEAR), + LineId::Exti6 => self.registers.imr1.modify(IMR1::MR6::CLEAR), + LineId::Exti7 => self.registers.imr1.modify(IMR1::MR7::CLEAR), + LineId::Exti8 => self.registers.imr1.modify(IMR1::MR8::CLEAR), + LineId::Exti9 => self.registers.imr1.modify(IMR1::MR9::CLEAR), + LineId::Exti10 => self.registers.imr1.modify(IMR1::MR10::CLEAR), + LineId::Exti11 => self.registers.imr1.modify(IMR1::MR11::CLEAR), + LineId::Exti12 => self.registers.imr1.modify(IMR1::MR12::CLEAR), + LineId::Exti13 => self.registers.imr1.modify(IMR1::MR13::CLEAR), + LineId::Exti14 => self.registers.imr1.modify(IMR1::MR14::CLEAR), + LineId::Exti15 => self.registers.imr1.modify(IMR1::MR15::CLEAR), + } + } + + pub fn unmask_interrupt(&self, lineid: LineId) { + match lineid { + LineId::Exti0 => self.registers.imr1.modify(IMR1::MR0::SET), + LineId::Exti1 => self.registers.imr1.modify(IMR1::MR1::SET), + LineId::Exti2 => self.registers.imr1.modify(IMR1::MR2::SET), + LineId::Exti3 => self.registers.imr1.modify(IMR1::MR3::SET), + LineId::Exti4 => self.registers.imr1.modify(IMR1::MR4::SET), + LineId::Exti5 => self.registers.imr1.modify(IMR1::MR5::SET), + LineId::Exti6 => self.registers.imr1.modify(IMR1::MR6::SET), + LineId::Exti7 => self.registers.imr1.modify(IMR1::MR7::SET), + LineId::Exti8 => self.registers.imr1.modify(IMR1::MR8::SET), + LineId::Exti9 => self.registers.imr1.modify(IMR1::MR9::SET), + LineId::Exti10 => self.registers.imr1.modify(IMR1::MR10::SET), + LineId::Exti11 => self.registers.imr1.modify(IMR1::MR11::SET), + LineId::Exti12 => self.registers.imr1.modify(IMR1::MR12::SET), + LineId::Exti13 => self.registers.imr1.modify(IMR1::MR13::SET), + LineId::Exti14 => self.registers.imr1.modify(IMR1::MR14::SET), + LineId::Exti15 => self.registers.imr1.modify(IMR1::MR15::SET), + } + } + + // Pending clear happens by writing 1 + pub fn clear_pending(&self, lineid: LineId) { + match lineid { + LineId::Exti0 => self.registers.pr1.write(PR1::PR0::SET), + LineId::Exti1 => self.registers.pr1.write(PR1::PR1::SET), + LineId::Exti2 => self.registers.pr1.write(PR1::PR2::SET), + LineId::Exti3 => self.registers.pr1.write(PR1::PR3::SET), + LineId::Exti4 => self.registers.pr1.write(PR1::PR4::SET), + LineId::Exti5 => self.registers.pr1.write(PR1::PR5::SET), + LineId::Exti6 => self.registers.pr1.write(PR1::PR6::SET), + LineId::Exti7 => self.registers.pr1.write(PR1::PR7::SET), + LineId::Exti8 => self.registers.pr1.write(PR1::PR8::SET), + LineId::Exti9 => self.registers.pr1.write(PR1::PR9::SET), + LineId::Exti10 => self.registers.pr1.write(PR1::PR10::SET), + LineId::Exti11 => self.registers.pr1.write(PR1::PR11::SET), + LineId::Exti12 => self.registers.pr1.write(PR1::PR12::SET), + LineId::Exti13 => self.registers.pr1.write(PR1::PR13::SET), + LineId::Exti14 => self.registers.pr1.write(PR1::PR14::SET), + LineId::Exti15 => self.registers.pr1.write(PR1::PR15::SET), + } + } + + pub fn is_pending(&self, lineid: LineId) -> bool { + let val = match lineid { + LineId::Exti0 => self.registers.pr1.read(PR1::PR0), + LineId::Exti1 => self.registers.pr1.read(PR1::PR1), + LineId::Exti2 => self.registers.pr1.read(PR1::PR2), + LineId::Exti3 => self.registers.pr1.read(PR1::PR3), + LineId::Exti4 => self.registers.pr1.read(PR1::PR4), + LineId::Exti5 => self.registers.pr1.read(PR1::PR5), + LineId::Exti6 => self.registers.pr1.read(PR1::PR6), + LineId::Exti7 => self.registers.pr1.read(PR1::PR7), + LineId::Exti8 => self.registers.pr1.read(PR1::PR8), + LineId::Exti9 => self.registers.pr1.read(PR1::PR9), + LineId::Exti10 => self.registers.pr1.read(PR1::PR10), + LineId::Exti11 => self.registers.pr1.read(PR1::PR11), + LineId::Exti12 => self.registers.pr1.read(PR1::PR12), + LineId::Exti13 => self.registers.pr1.read(PR1::PR13), + LineId::Exti14 => self.registers.pr1.read(PR1::PR14), + LineId::Exti15 => self.registers.pr1.read(PR1::PR15), + }; + val > 0 + } + + pub fn select_rising_trigger(&self, lineid: LineId) { + match lineid { + LineId::Exti0 => self.registers.rtsr1.modify(RTSR1::TR0::SET), + LineId::Exti1 => self.registers.rtsr1.modify(RTSR1::TR1::SET), + LineId::Exti2 => self.registers.rtsr1.modify(RTSR1::TR2::SET), + LineId::Exti3 => self.registers.rtsr1.modify(RTSR1::TR3::SET), + LineId::Exti4 => self.registers.rtsr1.modify(RTSR1::TR4::SET), + LineId::Exti5 => self.registers.rtsr1.modify(RTSR1::TR5::SET), + LineId::Exti6 => self.registers.rtsr1.modify(RTSR1::TR6::SET), + LineId::Exti7 => self.registers.rtsr1.modify(RTSR1::TR7::SET), + LineId::Exti8 => self.registers.rtsr1.modify(RTSR1::TR8::SET), + LineId::Exti9 => self.registers.rtsr1.modify(RTSR1::TR9::SET), + LineId::Exti10 => self.registers.rtsr1.modify(RTSR1::TR10::SET), + LineId::Exti11 => self.registers.rtsr1.modify(RTSR1::TR11::SET), + LineId::Exti12 => self.registers.rtsr1.modify(RTSR1::TR12::SET), + LineId::Exti13 => self.registers.rtsr1.modify(RTSR1::TR13::SET), + LineId::Exti14 => self.registers.rtsr1.modify(RTSR1::TR14::SET), + LineId::Exti15 => self.registers.rtsr1.modify(RTSR1::TR15::SET), + } + } + + pub fn deselect_rising_trigger(&self, lineid: LineId) { + match lineid { + LineId::Exti0 => self.registers.rtsr1.modify(RTSR1::TR0::CLEAR), + LineId::Exti1 => self.registers.rtsr1.modify(RTSR1::TR1::CLEAR), + LineId::Exti2 => self.registers.rtsr1.modify(RTSR1::TR2::CLEAR), + LineId::Exti3 => self.registers.rtsr1.modify(RTSR1::TR3::CLEAR), + LineId::Exti4 => self.registers.rtsr1.modify(RTSR1::TR4::CLEAR), + LineId::Exti5 => self.registers.rtsr1.modify(RTSR1::TR5::CLEAR), + LineId::Exti6 => self.registers.rtsr1.modify(RTSR1::TR6::CLEAR), + LineId::Exti7 => self.registers.rtsr1.modify(RTSR1::TR7::CLEAR), + LineId::Exti8 => self.registers.rtsr1.modify(RTSR1::TR8::CLEAR), + LineId::Exti9 => self.registers.rtsr1.modify(RTSR1::TR9::CLEAR), + LineId::Exti10 => self.registers.rtsr1.modify(RTSR1::TR10::CLEAR), + LineId::Exti11 => self.registers.rtsr1.modify(RTSR1::TR11::CLEAR), + LineId::Exti12 => self.registers.rtsr1.modify(RTSR1::TR12::CLEAR), + LineId::Exti13 => self.registers.rtsr1.modify(RTSR1::TR13::CLEAR), + LineId::Exti14 => self.registers.rtsr1.modify(RTSR1::TR14::CLEAR), + LineId::Exti15 => self.registers.rtsr1.modify(RTSR1::TR15::CLEAR), + } + } + + pub fn select_falling_trigger(&self, lineid: LineId) { + match lineid { + LineId::Exti0 => self.registers.ftsr1.modify(FTSR1::TR0::SET), + LineId::Exti1 => self.registers.ftsr1.modify(FTSR1::TR1::SET), + LineId::Exti2 => self.registers.ftsr1.modify(FTSR1::TR2::SET), + LineId::Exti3 => self.registers.ftsr1.modify(FTSR1::TR3::SET), + LineId::Exti4 => self.registers.ftsr1.modify(FTSR1::TR4::SET), + LineId::Exti5 => self.registers.ftsr1.modify(FTSR1::TR5::SET), + LineId::Exti6 => self.registers.ftsr1.modify(FTSR1::TR6::SET), + LineId::Exti7 => self.registers.ftsr1.modify(FTSR1::TR7::SET), + LineId::Exti8 => self.registers.ftsr1.modify(FTSR1::TR8::SET), + LineId::Exti9 => self.registers.ftsr1.modify(FTSR1::TR9::SET), + LineId::Exti10 => self.registers.ftsr1.modify(FTSR1::TR10::SET), + LineId::Exti11 => self.registers.ftsr1.modify(FTSR1::TR11::SET), + LineId::Exti12 => self.registers.ftsr1.modify(FTSR1::TR12::SET), + LineId::Exti13 => self.registers.ftsr1.modify(FTSR1::TR13::SET), + LineId::Exti14 => self.registers.ftsr1.modify(FTSR1::TR14::SET), + LineId::Exti15 => self.registers.ftsr1.modify(FTSR1::TR15::SET), + } + } + + pub fn deselect_falling_trigger(&self, lineid: LineId) { + match lineid { + LineId::Exti0 => self.registers.ftsr1.modify(FTSR1::TR0::CLEAR), + LineId::Exti1 => self.registers.ftsr1.modify(FTSR1::TR1::CLEAR), + LineId::Exti2 => self.registers.ftsr1.modify(FTSR1::TR2::CLEAR), + LineId::Exti3 => self.registers.ftsr1.modify(FTSR1::TR3::CLEAR), + LineId::Exti4 => self.registers.ftsr1.modify(FTSR1::TR4::CLEAR), + LineId::Exti5 => self.registers.ftsr1.modify(FTSR1::TR5::CLEAR), + LineId::Exti6 => self.registers.ftsr1.modify(FTSR1::TR6::CLEAR), + LineId::Exti7 => self.registers.ftsr1.modify(FTSR1::TR7::CLEAR), + LineId::Exti8 => self.registers.ftsr1.modify(FTSR1::TR8::CLEAR), + LineId::Exti9 => self.registers.ftsr1.modify(FTSR1::TR9::CLEAR), + LineId::Exti10 => self.registers.ftsr1.modify(FTSR1::TR10::CLEAR), + LineId::Exti11 => self.registers.ftsr1.modify(FTSR1::TR11::CLEAR), + LineId::Exti12 => self.registers.ftsr1.modify(FTSR1::TR12::CLEAR), + LineId::Exti13 => self.registers.ftsr1.modify(FTSR1::TR13::CLEAR), + LineId::Exti14 => self.registers.ftsr1.modify(FTSR1::TR14::CLEAR), + LineId::Exti15 => self.registers.ftsr1.modify(FTSR1::TR15::CLEAR), + } + } + + pub fn handle_interrupt(&self) { + let mut exti_pr: u32 = 0; + + // Read the `EXTI_PR` register and toggle the appropriate bits in + // `exti_pr`. Once that is done, write the value of `exti_pr` back. We + // can have a situation where memory value of `EXTI_PR` could have + // changed due to an external interrupt. `EXTI_PR` is a read/clear write + // 1 register (`rc_w1`). So, we only clear bits whose value has been + // transferred to `exti_pr`. + unsafe { + with_interrupts_disabled(|| { + exti_pr = self.registers.pr1.get(); + self.registers.pr1.set(exti_pr); + }); + } + + // ignore the "reserved" EXTI bits. Use bits [22:0]. See `EXTI_PR` for + // details. + exti_pr &= 0x007fffff; + + let mut flagged_bit = 0; + + // stay in loop until we have processed all the flagged event bits + while exti_pr != 0 { + if (exti_pr & 0b1) != 0 { + if let Some(d) = LineId::from_u8(flagged_bit) { + self.line_gpiopin_map[usize::from(d as u8)].map(|pin| pin.handle_interrupt()); + } + } + // move to next bit + flagged_bit += 1; + exti_pr >>= 1; + } + } +} + +/// Exti peripheral is clocked using PCLK2. However, PCLK2 does not seem to be +/// gated. The configuration registers for Exti is in Syscfg, so we need to +/// enable clock to Syscfg, when using Exti. +struct ExtiClock<'a>(&'a syscfg::Syscfg<'a>); + +impl ClockInterface for ExtiClock<'_> { + fn is_enabled(&self) -> bool { + self.0.is_enabled_clock() + } + + fn enable(&self) { + self.0.enable_clock(); + } + + fn disable(&self) { + self.0.disable_clock(); + } +} diff --git a/chips/stm32l4xx/src/flash.rs b/chips/stm32l4xx/src/flash.rs new file mode 100644 index 0000000000..9a189092ee --- /dev/null +++ b/chips/stm32l4xx/src/flash.rs @@ -0,0 +1,243 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +//! STM32L4xx flash driver +//! +//! This driver provides basic functionalities for the entire STM32L4 series. +//! +//! # Features +//! +//! - [x] Configuring latency based on the system clock frequency +//! +//! # Missing features +//! +//! - [ ] Support for different power supplies +//! - [ ] Instruction prefetch +//! - [ ] Instruction and data cache +//! +//! +//! # Usage +//! +//! To use this driver, a reference to the Flash peripheral is required: +//! +//! ```rust,ignore +//! // Inside the board main.rs +//! let flash = &peripherals.stm32l4.flash; +//! ``` +//! +//! ## Retrieve the current flash latency +//! +//! ```rust,ignore +//! let flash_latency = flash.get_latency() as usize; +//! debug!("Current flash latency is {}", flash_latency); +//! ``` + +use crate::chip_specific::flash::FlashChipSpecific as FlashChipSpecificTrait; +use crate::chip_specific::flash::RegisterToFlashLatency; +use crate::pwr::Pwr; + +use kernel::utilities::registers::interfaces::{ReadWriteable, Readable}; +use kernel::utilities::registers::{register_bitfields, ReadWrite, WriteOnly}; +use kernel::utilities::StaticRef; +use kernel::ErrorCode; + +use core::marker::PhantomData; + +#[repr(C)] +struct FlashRegisters { + /// Flash access control register + acr: ReadWrite, + /// Flash key register + pdkeyr: WriteOnly, + /// Flash option key register + keyr: WriteOnly, + /// Status register + sr: ReadWrite, + /// Control register + cr: ReadWrite, + /// Flash option control register + optcr: ReadWrite, +} + +register_bitfields![u32, + // FLASH access control register (ACR) + ACR [ + /// Latency (number of wait states). STM32L4x6: 3-bit field. + LATENCY OFFSET(0) NUMBITS(3) [ + WS0 = 0, + WS1 = 1, + WS2 = 2, + WS3 = 3, + WS4 = 4, + WS5 = 5, + WS6 = 6, + WS7 = 7 + ], + /// Prefetch enable + PRFTEN OFFSET(8) NUMBITS(1) [], + /// Instruction cache enable + ICEN OFFSET(9) NUMBITS(1) [], + /// Data cache enable + DCEN OFFSET(10) NUMBITS(1) [], + /// Instruction cache reset + ICRST OFFSET(11) NUMBITS(1) [], + /// Data cache reset + DCRST OFFSET(12) NUMBITS(1) [], + /// Flash power-down mode during run + RUN_PD OFFSET(13) NUMBITS(1) [], + /// Flash power-down mode during sleep + SLEEP_PD OFFSET(14) NUMBITS(1) [] + ], + + // FLASH status register (SR) + SR [ + /// End of operation + EOP OFFSET(0) NUMBITS(1) [], + /// Operation error + OPERR OFFSET(1) NUMBITS(1) [], + /// Programming error + PROGERR OFFSET(3) NUMBITS(1) [], + /// Write protection error + WRPERR OFFSET(4) NUMBITS(1) [], + /// Programming alignment error + PGAERR OFFSET(5) NUMBITS(1) [], + /// Size error + SIZERR OFFSET(6) NUMBITS(1) [], + /// Programming sequence error + PGSERR OFFSET(7) NUMBITS(1) [], + /// Fast programming data miss error + MISERR OFFSET(8) NUMBITS(1) [], + /// Fast programming error + FASTERR OFFSET(9) NUMBITS(1) [], + /// PCROP read error + RDERR OFFSET(14) NUMBITS(1) [], + /// Option validity error + OPTVERR OFFSET(15) NUMBITS(1) [], + /// Busy + BSY OFFSET(16) NUMBITS(1) [] + ], + + // FLASH control register (CR) + CR [ + /// Programming + PG OFFSET(0) NUMBITS(1) [], + /// Page erase + PER OFFSET(1) NUMBITS(1) [], + /// Mass erase bank 1 + MER1 OFFSET(2) NUMBITS(1) [], + /// Page number (for page erase) + PNB OFFSET(3) NUMBITS(8) [], + /// Bank selection for page erase (0: Bank1, 1: Bank2) + BKER OFFSET(11) NUMBITS(1) [], + /// Mass erase bank 2 + MER2 OFFSET(15) NUMBITS(1) [], + /// Start erase operation + START OFFSET(16) NUMBITS(1) [], + /// Options modification start + OPTSTRT OFFSET(17) NUMBITS(1) [], + /// Fast programming + FSTPG OFFSET(18) NUMBITS(1) [], + /// End of operation interrupt enable + EOPIE OFFSET(24) NUMBITS(1) [], + /// Error interrupt enable + ERRIE OFFSET(25) NUMBITS(1) [], + /// PCROP read error interrupt enable + RDERRIE OFFSET(26) NUMBITS(1) [], + /// Force option byte loading + OBL_LAUNCH OFFSET(27) NUMBITS(1) [], + /// Option bytes lock + OPTLOCK OFFSET(30) NUMBITS(1) [], + /// FLASH control register lock + LOCK OFFSET(31) NUMBITS(1) [] + ], + + // FLASH option register (OPTR) — named OPTCR here to keep code stable + OPTCR [ + /// Read protection level + RDP OFFSET(0) NUMBITS(8) [], + /// BOR reset level + BOR_LEV OFFSET(8) NUMBITS(2) [], + /// Reset generated when entering Stop mode (active low) + nRST_STOP OFFSET(12) NUMBITS(1) [], + /// Reset generated when entering Standby mode (active low) + nRST_STDBY OFFSET(13) NUMBITS(1) [], + /// Reset generated when entering Shutdown mode (active low) + nRST_SHDW OFFSET(14) NUMBITS(1) [], + /// Independent watchdog selection + IWDG_SW OFFSET(16) NUMBITS(1) [], + /// Independent watchdog counter freeze in Stop mode + IWDG_STOP OFFSET(17) NUMBITS(1) [], + /// Independent watchdog counter freeze in Standby mode + IWDG_STDBY OFFSET(18) NUMBITS(1) [], + /// Window watchdog selection + WWDG_SW OFFSET(19) NUMBITS(1) [], + /// Boot from Bank 2 (if dual-bank supported) + BFB2 OFFSET(20) NUMBITS(1) [], + /// Dual-bank configuration (if available) + DUALBANK OFFSET(21) NUMBITS(1) [] + ], +]; + +// STM32L4xx FLASH base address +const FLASH_BASE: StaticRef = + unsafe { StaticRef::new(0x40022000 as *const FlashRegisters) }; + +/// Main Flash struct +pub struct Flash { + registers: StaticRef, + pwr: Pwr, + _marker: PhantomData, +} + +impl Flash { + // Flash constructor. It should be called when creating Stm32l4xxDefaultPeripherals. + pub(crate) fn new(pwr: Pwr) -> Self { + Self { + registers: FLASH_BASE, + pwr, + _marker: PhantomData, + } + } + + fn read_latency_from_register(&self) -> u32 { + self.registers.acr.read(ACR::LATENCY) + } + + // NOTE: This method is pub(crate) to prevent modifying the flash latency from board files. + // Flash latency is dependent on the system clock frequency. Other peripherals will modify this + // when appropriate. + pub(crate) fn set_latency(&self, sys_clock_frequency: usize) -> Result<(), ErrorCode> { + if !self.pwr.is_vos_ready() { + return Err(ErrorCode::BUSY); + } + + let flash_latency = + FlashChipSpecific::get_number_wait_cycles_based_on_frequency_and_voltage( + sys_clock_frequency, + self.pwr.get_vos() as usize, + ); + + self.registers + .acr + .modify(ACR::LATENCY.val(flash_latency.into())); + // Wait until the flash latency is set + // The value 16 was chosen randomly, but it behaves well in tests. It can be tuned in a + // future revision of the driver. + for _ in 0..16 { + if self.get_latency() == flash_latency { + return Ok(()); + } + } + + // Return BUSY if setting the frequency took too long. The caller can either: + // + // + recall this method + // + or busy wait get_latency() until the flash latency has the desired value + Err(ErrorCode::BUSY) + } + + pub(crate) fn get_latency(&self) -> FlashChipSpecific::FlashLatency { + FlashChipSpecific::FlashLatency::convert_register_to_enum(self.read_latency_from_register()) + } +} diff --git a/chips/stm32l4xx/src/gpio.rs b/chips/stm32l4xx/src/gpio.rs new file mode 100644 index 0000000000..406ea76956 --- /dev/null +++ b/chips/stm32l4xx/src/gpio.rs @@ -0,0 +1,1309 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +use cortexm4f::support::with_interrupts_disabled; +use enum_primitive::cast::FromPrimitive; +use enum_primitive::enum_from_primitive; +use kernel::hil; +use kernel::platform::chip::ClockInterface; +use kernel::utilities::cells::OptionalCell; +use kernel::utilities::registers::interfaces::{ReadWriteable, Readable, Writeable}; +use kernel::utilities::registers::{register_bitfields, ReadOnly, ReadWrite, WriteOnly}; +use kernel::utilities::StaticRef; + +use crate::clocks::{phclk, Stm32l4Clocks}; +use crate::exti::{self, LineId}; + +/// General-purpose I/Os +#[repr(C)] +struct GpioRegisters { + /// GPIO port mode register + moder: ReadWrite, + /// GPIO port output type register + otyper: ReadWrite, + /// GPIO port output speed register + ospeedr: ReadWrite, + /// GPIO port pull-up/pull-down register + pupdr: ReadWrite, + /// GPIO port input data register + idr: ReadOnly, + /// GPIO port output data register + odr: ReadWrite, + /// GPIO port bit set/reset register + bsrr: WriteOnly, + /// GPIO port configuration lock register + lckr: ReadWrite, + /// GPIO alternate function low register + afrl: ReadWrite, + /// GPIO alternate function high register + afrh: ReadWrite, + /// GPIO Bit Reset register + brr: WriteOnly, + /// GPIO analog switch control register + ascr: ReadWrite, +} + +register_bitfields![u32, + MODER [ + /// Port x configuration bits (y = 0..15) + MODER15 OFFSET(30) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + MODER14 OFFSET(28) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + MODER13 OFFSET(26) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + MODER12 OFFSET(24) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + MODER11 OFFSET(22) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + MODER10 OFFSET(20) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + MODER9 OFFSET(18) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + MODER8 OFFSET(16) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + MODER7 OFFSET(14) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + MODER6 OFFSET(12) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + MODER5 OFFSET(10) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + MODER4 OFFSET(8) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + MODER3 OFFSET(6) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + MODER2 OFFSET(4) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + MODER1 OFFSET(2) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + MODER0 OFFSET(0) NUMBITS(2) [] + ], + OTYPER [ + /// Port x configuration bits (y = 0..15) + OT15 OFFSET(15) NUMBITS(1) [], + /// Port x configuration bits (y = 0..15) + OT14 OFFSET(14) NUMBITS(1) [], + /// Port x configuration bits (y = 0..15) + OT13 OFFSET(13) NUMBITS(1) [], + /// Port x configuration bits (y = 0..15) + OT12 OFFSET(12) NUMBITS(1) [], + /// Port x configuration bits (y = 0..15) + OT11 OFFSET(11) NUMBITS(1) [], + /// Port x configuration bits (y = 0..15) + OT10 OFFSET(10) NUMBITS(1) [], + /// Port x configuration bits (y = 0..15) + OT9 OFFSET(9) NUMBITS(1) [], + /// Port x configuration bits (y = 0..15) + OT8 OFFSET(8) NUMBITS(1) [], + /// Port x configuration bits (y = 0..15) + OT7 OFFSET(7) NUMBITS(1) [], + /// Port x configuration bits (y = 0..15) + OT6 OFFSET(6) NUMBITS(1) [], + /// Port x configuration bits (y = 0..15) + OT5 OFFSET(5) NUMBITS(1) [], + /// Port x configuration bits (y = 0..15) + OT4 OFFSET(4) NUMBITS(1) [], + /// Port x configuration bits (y = 0..15) + OT3 OFFSET(3) NUMBITS(1) [], + /// Port x configuration bits (y = 0..15) + OT2 OFFSET(2) NUMBITS(1) [], + /// Port x configuration bits (y = 0..15) + OT1 OFFSET(1) NUMBITS(1) [], + /// Port x configuration bits (y = 0..15) + OT0 OFFSET(0) NUMBITS(1) [] + ], + OSPEEDR [ + /// Port x configuration bits (y = 0..15) + OSPEEDR15 OFFSET(30) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + OSPEEDR14 OFFSET(28) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + OSPEEDR13 OFFSET(26) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + OSPEEDR12 OFFSET(24) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + OSPEEDR11 OFFSET(22) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + OSPEEDR10 OFFSET(20) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + OSPEEDR9 OFFSET(18) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + OSPEEDR8 OFFSET(16) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + OSPEEDR7 OFFSET(14) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + OSPEEDR6 OFFSET(12) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + OSPEEDR5 OFFSET(10) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + OSPEEDR4 OFFSET(8) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + OSPEEDR3 OFFSET(6) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + OSPEEDR2 OFFSET(4) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + OSPEEDR1 OFFSET(2) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + OSPEEDR0 OFFSET(0) NUMBITS(2) [] + ], + PUPDR [ + /// Port x configuration bits (y = 0..15) + PUPDR15 OFFSET(30) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + PUPDR14 OFFSET(28) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + PUPDR13 OFFSET(26) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + PUPDR12 OFFSET(24) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + PUPDR11 OFFSET(22) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + PUPDR10 OFFSET(20) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + PUPDR9 OFFSET(18) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + PUPDR8 OFFSET(16) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + PUPDR7 OFFSET(14) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + PUPDR6 OFFSET(12) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + PUPDR5 OFFSET(10) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + PUPDR4 OFFSET(8) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + PUPDR3 OFFSET(6) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + PUPDR2 OFFSET(4) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + PUPDR1 OFFSET(2) NUMBITS(2) [], + /// Port x configuration bits (y = 0..15) + PUPDR0 OFFSET(0) NUMBITS(2) [] + ], + IDR [ + /// Port input data (y = 0..15) + IDR15 OFFSET(15) NUMBITS(1) [], + /// Port input data (y = 0..15) + IDR14 OFFSET(14) NUMBITS(1) [], + /// Port input data (y = 0..15) + IDR13 OFFSET(13) NUMBITS(1) [], + /// Port input data (y = 0..15) + IDR12 OFFSET(12) NUMBITS(1) [], + /// Port input data (y = 0..15) + IDR11 OFFSET(11) NUMBITS(1) [], + /// Port input data (y = 0..15) + IDR10 OFFSET(10) NUMBITS(1) [], + /// Port input data (y = 0..15) + IDR9 OFFSET(9) NUMBITS(1) [], + /// Port input data (y = 0..15) + IDR8 OFFSET(8) NUMBITS(1) [], + /// Port input data (y = 0..15) + IDR7 OFFSET(7) NUMBITS(1) [], + /// Port input data (y = 0..15) + IDR6 OFFSET(6) NUMBITS(1) [], + /// Port input data (y = 0..15) + IDR5 OFFSET(5) NUMBITS(1) [], + /// Port input data (y = 0..15) + IDR4 OFFSET(4) NUMBITS(1) [], + /// Port input data (y = 0..15) + IDR3 OFFSET(3) NUMBITS(1) [], + /// Port input data (y = 0..15) + IDR2 OFFSET(2) NUMBITS(1) [], + /// Port input data (y = 0..15) + IDR1 OFFSET(1) NUMBITS(1) [], + /// Port input data (y = 0..15) + IDR0 OFFSET(0) NUMBITS(1) [] + ], + ODR [ + /// Port output data (y = 0..15) + ODR15 OFFSET(15) NUMBITS(1) [], + /// Port output data (y = 0..15) + ODR14 OFFSET(14) NUMBITS(1) [], + /// Port output data (y = 0..15) + ODR13 OFFSET(13) NUMBITS(1) [], + /// Port output data (y = 0..15) + ODR12 OFFSET(12) NUMBITS(1) [], + /// Port output data (y = 0..15) + ODR11 OFFSET(11) NUMBITS(1) [], + /// Port output data (y = 0..15) + ODR10 OFFSET(10) NUMBITS(1) [], + /// Port output data (y = 0..15) + ODR9 OFFSET(9) NUMBITS(1) [], + /// Port output data (y = 0..15) + ODR8 OFFSET(8) NUMBITS(1) [], + /// Port output data (y = 0..15) + ODR7 OFFSET(7) NUMBITS(1) [], + /// Port output data (y = 0..15) + ODR6 OFFSET(6) NUMBITS(1) [], + /// Port output data (y = 0..15) + ODR5 OFFSET(5) NUMBITS(1) [], + /// Port output data (y = 0..15) + ODR4 OFFSET(4) NUMBITS(1) [], + /// Port output data (y = 0..15) + ODR3 OFFSET(3) NUMBITS(1) [], + /// Port output data (y = 0..15) + ODR2 OFFSET(2) NUMBITS(1) [], + /// Port output data (y = 0..15) + ODR1 OFFSET(1) NUMBITS(1) [], + /// Port output data (y = 0..15) + ODR0 OFFSET(0) NUMBITS(1) [] + ], + BSRR [ + /// Port x reset bit y (y = 0..15) + BR15 OFFSET(31) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR14 OFFSET(30) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR13 OFFSET(29) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR12 OFFSET(28) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR11 OFFSET(27) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR10 OFFSET(26) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR9 OFFSET(25) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR8 OFFSET(24) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR7 OFFSET(23) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR6 OFFSET(22) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR5 OFFSET(21) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR4 OFFSET(20) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR3 OFFSET(19) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR2 OFFSET(18) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR1 OFFSET(17) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR0 OFFSET(16) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS15 OFFSET(15) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS14 OFFSET(14) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS13 OFFSET(13) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS12 OFFSET(12) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS11 OFFSET(11) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS10 OFFSET(10) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS9 OFFSET(9) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS8 OFFSET(8) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS7 OFFSET(7) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS6 OFFSET(6) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS5 OFFSET(5) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS4 OFFSET(4) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS3 OFFSET(3) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS2 OFFSET(2) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS1 OFFSET(1) NUMBITS(1) [], + /// Port x set bit y (y = 0..15) + BS0 OFFSET(0) NUMBITS(1) [] + ], + LCKR [ + /// Port x lock bit y (y = 0..15) + LCKK OFFSET(16) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK15 OFFSET(15) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK14 OFFSET(14) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK13 OFFSET(13) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK12 OFFSET(12) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK11 OFFSET(11) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK10 OFFSET(10) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK9 OFFSET(9) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK8 OFFSET(8) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK7 OFFSET(7) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK6 OFFSET(6) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK5 OFFSET(5) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK4 OFFSET(4) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK3 OFFSET(3) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK2 OFFSET(2) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK1 OFFSET(1) NUMBITS(1) [], + /// Port x lock bit y (y = 0..15) + LCK0 OFFSET(0) NUMBITS(1) [] + ], + AFRL [ + /// Alternate function selection for port x bit y (y = 0..7) + AFRL7 OFFSET(28) NUMBITS(4) [], + /// Alternate function selection for port x bit y (y = 0..7) + AFRL6 OFFSET(24) NUMBITS(4) [], + /// Alternate function selection for port x bit y (y = 0..7) + AFRL5 OFFSET(20) NUMBITS(4) [], + /// Alternate function selection for port x bit y (y = 0..7) + AFRL4 OFFSET(16) NUMBITS(4) [], + /// Alternate function selection for port x bit y (y = 0..7) + AFRL3 OFFSET(12) NUMBITS(4) [], + /// Alternate function selection for port x bit y (y = 0..7) + AFRL2 OFFSET(8) NUMBITS(4) [], + /// Alternate function selection for port x bit y (y = 0..7) + AFRL1 OFFSET(4) NUMBITS(4) [], + /// Alternate function selection for port x bit y (y = 0..7) + AFRL0 OFFSET(0) NUMBITS(4) [] + ], + AFRH [ + /// Alternate function selection for port x bit y (y = 8..15) + AFRH15 OFFSET(28) NUMBITS(4) [], + /// Alternate function selection for port x bit y (y = 8..15) + AFRH14 OFFSET(24) NUMBITS(4) [], + /// Alternate function selection for port x bit y (y = 8..15) + AFRH13 OFFSET(20) NUMBITS(4) [], + /// Alternate function selection for port x bit y (y = 8..15) + AFRH12 OFFSET(16) NUMBITS(4) [], + /// Alternate function selection for port x bit y (y = 8..15) + AFRH11 OFFSET(12) NUMBITS(4) [], + /// Alternate function selection for port x bit y (y = 8..15) + AFRH10 OFFSET(8) NUMBITS(4) [], + /// Alternate function selection for port x bit y (y = 8..15) + AFRH9 OFFSET(4) NUMBITS(4) [], + /// Alternate function selection for port x bit y (y = 8..15) + AFRH8 OFFSET(0) NUMBITS(4) [] + ], + BRR [ + /// Port x reset bit y (y = 0..15) + BR15 OFFSET(15) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR14 OFFSET(14) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR13 OFFSET(13) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR12 OFFSET(12) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR11 OFFSET(11) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR10 OFFSET(10) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR9 OFFSET(9) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR8 OFFSET(8) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR7 OFFSET(7) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR6 OFFSET(6) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR5 OFFSET(5) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR4 OFFSET(4) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR3 OFFSET(3) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR2 OFFSET(2) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR1 OFFSET(1) NUMBITS(1) [], + /// Port x reset bit y (y = 0..15) + BR0 OFFSET(0) NUMBITS(1) [], + ], + ASCR[ + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC15 OFFSET(15) NUMBITS(1) [], + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC14 OFFSET(14) NUMBITS(1) [], + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC13 OFFSET(13) NUMBITS(1) [], + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC12 OFFSET(12) NUMBITS(1) [], + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC11 OFFSET(11) NUMBITS(1) [], + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC10 OFFSET(10) NUMBITS(1) [], + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC9 OFFSET(9) NUMBITS(1) [], + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC8 OFFSET(8) NUMBITS(1) [], + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC7 OFFSET(7) NUMBITS(1) [], + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC6 OFFSET(6) NUMBITS(1) [], + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC5 OFFSET(5) NUMBITS(1) [], + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC4 OFFSET(4) NUMBITS(1) [], + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC3 OFFSET(3) NUMBITS(1) [], + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC2 OFFSET(2) NUMBITS(1) [], + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC1 OFFSET(1) NUMBITS(1) [], + /// Port x analog switch control I/O pin y (y = 15 to 0) + ASC0 OFFSET(0) NUMBITS(1) [], + ] + +]; +const GPIOH_BASE: StaticRef = + unsafe { StaticRef::new(0x48001C00 as *const GpioRegisters) }; + +const GPIOG_BASE: StaticRef = + unsafe { StaticRef::new(0x48001800 as *const GpioRegisters) }; + +const GPIOF_BASE: StaticRef = + unsafe { StaticRef::new(0x48001400 as *const GpioRegisters) }; + +const GPIOE_BASE: StaticRef = + unsafe { StaticRef::new(0x48001000 as *const GpioRegisters) }; + +const GPIOD_BASE: StaticRef = + unsafe { StaticRef::new(0x48000C00 as *const GpioRegisters) }; + +const GPIOC_BASE: StaticRef = + unsafe { StaticRef::new(0x48000800 as *const GpioRegisters) }; + +const GPIOB_BASE: StaticRef = + unsafe { StaticRef::new(0x48000400 as *const GpioRegisters) }; + +const GPIOA_BASE: StaticRef = + unsafe { StaticRef::new(0x48000000 as *const GpioRegisters) }; + +#[repr(u32)] +pub enum PortId { + A = 0b000, + B = 0b001, + C = 0b010, + D = 0b011, + E = 0b100, + F = 0b101, + G = 0b110, + H = 0b111, +} + +#[rustfmt::skip] +#[repr(u8)] +#[derive(Copy, Clone)] +pub enum PinId { + PA00 = 0b0000000, PA01 = 0b0000001, PA02 = 0b0000010, PA03 = 0b0000011, + PA04 = 0b0000100, PA05 = 0b0000101, PA06 = 0b0000110, PA07 = 0b0000111, + PA08 = 0b0001000, PA09 = 0b0001001, PA10 = 0b0001010, PA11 = 0b0001011, + PA12 = 0b0001100, PA13 = 0b0001101, PA14 = 0b0001110, PA15 = 0b0001111, + + PB00 = 0b0010000, PB01 = 0b0010001, PB02 = 0b0010010, PB03 = 0b0010011, + PB04 = 0b0010100, PB05 = 0b0010101, PB06 = 0b0010110, PB07 = 0b0010111, + PB08 = 0b0011000, PB09 = 0b0011001, PB10 = 0b0011010, PB11 = 0b0011011, + PB12 = 0b0011100, PB13 = 0b0011101, PB14 = 0b0011110, PB15 = 0b0011111, + + PC00 = 0b0100000, PC01 = 0b0100001, PC02 = 0b0100010, PC03 = 0b0100011, + PC04 = 0b0100100, PC05 = 0b0100101, PC06 = 0b0100110, PC07 = 0b0100111, + PC08 = 0b0101000, PC09 = 0b0101001, PC10 = 0b0101010, PC11 = 0b0101011, + PC12 = 0b0101100, PC13 = 0b0101101, PC14 = 0b0101110, PC15 = 0b0101111, + + PD00 = 0b0110000, PD01 = 0b0110001, PD02 = 0b0110010, PD03 = 0b0110011, + PD04 = 0b0110100, PD05 = 0b0110101, PD06 = 0b0110110, PD07 = 0b0110111, + PD08 = 0b0111000, PD09 = 0b0111001, PD10 = 0b0111010, PD11 = 0b0111011, + PD12 = 0b0111100, PD13 = 0b0111101, PD14 = 0b0111110, PD15 = 0b0111111, + + PE00 = 0b1000000, PE01 = 0b1000001, PE02 = 0b1000010, PE03 = 0b1000011, + PE04 = 0b1000100, PE05 = 0b1000101, PE06 = 0b1000110, PE07 = 0b1000111, + PE08 = 0b1001000, PE09 = 0b1001001, PE10 = 0b1001010, PE11 = 0b1001011, + PE12 = 0b1001100, PE13 = 0b1001101, PE14 = 0b1001110, PE15 = 0b1001111, + + PF00 = 0b1010000, PF01 = 0b1010001, PF02 = 0b1010010, PF03 = 0b1010011, + PF04 = 0b1010100, PF05 = 0b1010101, PF06 = 0b1010110, PF07 = 0b1010111, + PF08 = 0b1011000, PF09 = 0b1011001, PF10 = 0b1011010, PF11 = 0b1011011, + PF12 = 0b1011100, PF13 = 0b1011101, PF14 = 0b1011110, PF15 = 0b1011111, + + PG00 = 0b1100000, PG01 = 0b1100001, PG02 = 0b1100010, PG03 = 0b1100011, + PG04 = 0b1100100, PG05 = 0b1100101, PG06 = 0b1100110, PG07 = 0b1100111, + PG08 = 0b1101000, PG09 = 0b1101001, PG10 = 0b1101010, PG11 = 0b1101011, + PG12 = 0b1101100, PG13 = 0b1101101, PG14 = 0b1101110, PG15 = 0b1101111, + + PH00 = 0b1110000, PH01 = 0b1110001, +} + +impl<'a> GpioPorts<'a> { + pub fn get_pin(&self, pinid: PinId) -> Option<&Pin<'a>> { + let mut port_num: u8 = pinid as u8; + + // Right shift p by 4 bits, so we can get rid of pin bits + port_num >>= 4; + + let mut pin_num: u8 = pinid as u8; + // Mask top 3 bits, so can get only the suffix + pin_num &= 0b0001111; + + self.pins[usize::from(port_num)][usize::from(pin_num)].as_ref() + } + + pub fn get_port(&self, pinid: PinId) -> &Port { + let mut port_num: u8 = pinid as u8; + + // Right shift p by 4 bits, so we can get rid of pin bits + port_num >>= 4; + &self.ports[usize::from(port_num)] + } + + pub fn get_port_from_port_id(&self, portid: PortId) -> &Port { + &self.ports[portid as usize] + } +} + +impl PinId { + // extract the last 4 bits. [3:0] is the pin number, [6:4] is the port + // number + pub fn get_pin_number(&self) -> u8 { + let mut pin_num = *self as u8; + + pin_num &= 0b00001111; + pin_num + } + + // extract bits [6:4], which is the port number + pub fn get_port_number(&self) -> u8 { + let mut port_num: u8 = *self as u8; + + // Right shift p by 4 bits, so we can get rid of pin bits + port_num >>= 4; + port_num + } +} + +enum_from_primitive! { + #[repr(u32)] + #[derive(PartialEq)] + /// GPIO pin mode [^1] + /// + /// [^1]: Section 7.1.4, page 187 of reference manual + pub enum Mode { + Input = 0b00, + GeneralPurposeOutputMode = 0b01, + AlternateFunctionMode = 0b10, + AnalogMode = 0b11, + } +} + +enum_from_primitive! { + #[repr(u32)] + enum PullUpPullDown { + NoPullUpPullDown = 0b00, + PullUp = 0b01, + PullDown = 0b10, + } +} + +/// Alternate functions that may be assigned to a `Pin`. +/// +/// GPIO pins on the STM32L4xx may serve multiple functions. In addition to +/// the default functionality, each pin can be assigned up to sixteen different +/// alternate functions. The various functions for each pin are described in +/// "Alternate Function"" section of the STM32L4xx datasheet[^1]. +/// +/// Alternate Function bit mapping is shown here[^2]. +/// +/// [^1]: Section 4, Pinout and pin description, Table 11. Alternate function, +/// pages 59-66 +/// +/// [^2]: Section 7.4.9, page 192 of Reference Manual +#[repr(u32)] +pub enum AlternateFunction { + AF0 = 0b0000, + AF1 = 0b0001, + AF2 = 0b0010, + AF3 = 0b0011, + AF4 = 0b0100, + AF5 = 0b0101, + AF6 = 0b0110, + AF7 = 0b0111, + AF8 = 0b1000, + AF9 = 0b1001, + AF10 = 0b1010, + AF11 = 0b1011, + AF12 = 0b1100, + AF13 = 0b1101, + AF14 = 0b1110, + AF15 = 0b1111, +} + +pub struct Port<'a> { + registers: StaticRef, + clock: PortClock<'a>, +} + +macro_rules! declare_gpio_pins { + ($($pin:ident)*, $exti:expr) => { + [ + $(Some(Pin::new(PinId::$pin, $exti)), )* + ] + } +} + +// Note: This would probably be better structured as each port holding +// the pins associated with it, but here they are kept separate for +// historical reasons. If writing new GPIO code, look elsewhere for +// a template on how to structure the relationship between ports and pins. +// We need to use `Option`, instead of just `Pin` because GPIOH has +// only two pins - PH00 and PH01, rather than the usual sixteen pins. +pub struct GpioPorts<'a> { + ports: [Port<'a>; 8], + pub pins: [[Option>; 16]; 8], +} + +impl<'a> GpioPorts<'a> { + pub fn new(clocks: &'a dyn Stm32l4Clocks, exti: &'a exti::Exti<'a>) -> Self { + Self { + ports: [ + Port { + registers: GPIOA_BASE, + clock: PortClock(phclk::PeripheralClock::new( + phclk::PeripheralClockType::AHB2(phclk::HCLK2::GPIOA), + clocks, + )), + }, + Port { + registers: GPIOB_BASE, + clock: PortClock(phclk::PeripheralClock::new( + phclk::PeripheralClockType::AHB2(phclk::HCLK2::GPIOB), + clocks, + )), + }, + Port { + registers: GPIOC_BASE, + clock: PortClock(phclk::PeripheralClock::new( + phclk::PeripheralClockType::AHB2(phclk::HCLK2::GPIOC), + clocks, + )), + }, + Port { + registers: GPIOD_BASE, + clock: PortClock(phclk::PeripheralClock::new( + phclk::PeripheralClockType::AHB2(phclk::HCLK2::GPIOD), + clocks, + )), + }, + Port { + registers: GPIOE_BASE, + clock: PortClock(phclk::PeripheralClock::new( + phclk::PeripheralClockType::AHB2(phclk::HCLK2::GPIOE), + clocks, + )), + }, + Port { + registers: GPIOF_BASE, + clock: PortClock(phclk::PeripheralClock::new( + phclk::PeripheralClockType::AHB2(phclk::HCLK2::GPIOF), + clocks, + )), + }, + Port { + registers: GPIOG_BASE, + clock: PortClock(phclk::PeripheralClock::new( + phclk::PeripheralClockType::AHB2(phclk::HCLK2::GPIOG), + clocks, + )), + }, + Port { + registers: GPIOH_BASE, + clock: PortClock(phclk::PeripheralClock::new( + phclk::PeripheralClockType::AHB2(phclk::HCLK2::GPIOH), + clocks, + )), + }, + ], + pins: [ + declare_gpio_pins! { + PA00 PA01 PA02 PA03 PA04 PA05 PA06 PA07 + PA08 PA09 PA10 PA11 PA12 PA13 PA14 PA15, exti + }, + declare_gpio_pins! { + PB00 PB01 PB02 PB03 PB04 PB05 PB06 PB07 + PB08 PB09 PB10 PB11 PB12 PB13 PB14 PB15, exti + }, + declare_gpio_pins! { + PC00 PC01 PC02 PC03 PC04 PC05 PC06 PC07 + PC08 PC09 PC10 PC11 PC12 PC13 PC14 PC15, exti + }, + declare_gpio_pins! { + PD00 PD01 PD02 PD03 PD04 PD05 PD06 PD07 + PD08 PD09 PD10 PD11 PD12 PD13 PD14 PD15, exti + }, + declare_gpio_pins! { + PE00 PE01 PE02 PE03 PE04 PE05 PE06 PE07 + PE08 PE09 PE10 PE11 PE12 PE13 PE14 PE15, exti + }, + declare_gpio_pins! { + PF00 PF01 PF02 PF03 PF04 PF05 PF06 PF07 + PF08 PF09 PF10 PF11 PF12 PF13 PF14 PF15, exti + }, + declare_gpio_pins! { + PG00 PG01 PG02 PG03 PG04 PG05 PG06 PG07 + PG08 PG09 PG10 PG11 PG12 PG13 PG14 PG15, exti + }, + [ + Some(Pin::new(PinId::PH00, exti)), + Some(Pin::new(PinId::PH01, exti)), + None, + None, + None, + None, + None, + None, + None, + None, + None, + None, + None, + None, + None, + None, + ], + ], + } + } + + pub fn setup_circular_deps(&'a self) { + for pin_group in self.pins.iter() { + for pin in pin_group { + pin.as_ref().map(|p| p.set_ports_ref(self)); + } + } + } +} + +impl Port<'_> { + pub fn is_enabled_clock(&self) -> bool { + self.clock.is_enabled() + } + + pub fn enable_clock(&self) { + self.clock.enable(); + } + + pub fn disable_clock(&self) { + self.clock.disable(); + } +} + +struct PortClock<'a>(phclk::PeripheralClock<'a>); + +impl ClockInterface for PortClock<'_> { + fn is_enabled(&self) -> bool { + self.0.is_enabled() + } + + fn enable(&self) { + self.0.enable(); + } + + fn disable(&self) { + self.0.disable(); + } +} + +// `exti_lineid` is used to configure EXTI settings for the Pin. +pub struct Pin<'a> { + pinid: PinId, + ports_ref: OptionalCell<&'a GpioPorts<'a>>, + exti: &'a exti::Exti<'a>, + client: OptionalCell<&'a dyn hil::gpio::Client>, + exti_lineid: OptionalCell, +} + +impl<'a> Pin<'a> { + pub const fn new(pinid: PinId, exti: &'a exti::Exti<'a>) -> Self { + Self { + pinid, + ports_ref: OptionalCell::empty(), + exti, + client: OptionalCell::empty(), + exti_lineid: OptionalCell::empty(), + } + } + + pub fn set_ports_ref(&self, ports: &'a GpioPorts<'a>) { + self.ports_ref.set(ports); + } + + pub fn set_client(&self, client: &'a dyn hil::gpio::Client) { + self.client.set(client); + } + + pub fn handle_interrupt(&self) { + self.client.map(|client| client.fired()); + } + + pub fn get_mode(&self) -> Mode { + let port = self.ports_ref.unwrap_or_panic().get_port(self.pinid); // Unwrap fail = + + let val = match self.pinid.get_pin_number() { + 0b0000 => port.registers.moder.read(MODER::MODER0), + 0b0001 => port.registers.moder.read(MODER::MODER1), + 0b0010 => port.registers.moder.read(MODER::MODER2), + 0b0011 => port.registers.moder.read(MODER::MODER3), + 0b0100 => port.registers.moder.read(MODER::MODER4), + 0b0101 => port.registers.moder.read(MODER::MODER5), + 0b0110 => port.registers.moder.read(MODER::MODER6), + 0b0111 => port.registers.moder.read(MODER::MODER7), + 0b1000 => port.registers.moder.read(MODER::MODER8), + 0b1001 => port.registers.moder.read(MODER::MODER9), + 0b1010 => port.registers.moder.read(MODER::MODER10), + 0b1011 => port.registers.moder.read(MODER::MODER11), + 0b1100 => port.registers.moder.read(MODER::MODER12), + 0b1101 => port.registers.moder.read(MODER::MODER13), + 0b1110 => port.registers.moder.read(MODER::MODER14), + 0b1111 => port.registers.moder.read(MODER::MODER15), + _ => 0, + }; + + Mode::from_u32(val).unwrap_or(Mode::Input) + } + + pub fn set_mode(&self, mode: Mode) { + let port = self.ports_ref.unwrap_or_panic().get_port(self.pinid); // Unwrap fail = + + match self.pinid.get_pin_number() { + 0b0000 => port.registers.moder.modify(MODER::MODER0.val(mode as u32)), + 0b0001 => port.registers.moder.modify(MODER::MODER1.val(mode as u32)), + 0b0010 => port.registers.moder.modify(MODER::MODER2.val(mode as u32)), + 0b0011 => port.registers.moder.modify(MODER::MODER3.val(mode as u32)), + 0b0100 => port.registers.moder.modify(MODER::MODER4.val(mode as u32)), + 0b0101 => port.registers.moder.modify(MODER::MODER5.val(mode as u32)), + 0b0110 => port.registers.moder.modify(MODER::MODER6.val(mode as u32)), + 0b0111 => port.registers.moder.modify(MODER::MODER7.val(mode as u32)), + 0b1000 => port.registers.moder.modify(MODER::MODER8.val(mode as u32)), + 0b1001 => port.registers.moder.modify(MODER::MODER9.val(mode as u32)), + 0b1010 => port.registers.moder.modify(MODER::MODER10.val(mode as u32)), + 0b1011 => port.registers.moder.modify(MODER::MODER11.val(mode as u32)), + 0b1100 => port.registers.moder.modify(MODER::MODER12.val(mode as u32)), + 0b1101 => port.registers.moder.modify(MODER::MODER13.val(mode as u32)), + 0b1110 => port.registers.moder.modify(MODER::MODER14.val(mode as u32)), + 0b1111 => port.registers.moder.modify(MODER::MODER15.val(mode as u32)), + _ => {} + } + } + + pub fn set_alternate_function(&self, af: AlternateFunction) { + let port = self.ports_ref.unwrap_or_panic().get_port(self.pinid); // Unwrap fail = + + match self.pinid.get_pin_number() { + 0b0000 => port.registers.afrl.modify(AFRL::AFRL0.val(af as u32)), + 0b0001 => port.registers.afrl.modify(AFRL::AFRL1.val(af as u32)), + 0b0010 => port.registers.afrl.modify(AFRL::AFRL2.val(af as u32)), + 0b0011 => port.registers.afrl.modify(AFRL::AFRL3.val(af as u32)), + 0b0100 => port.registers.afrl.modify(AFRL::AFRL4.val(af as u32)), + 0b0101 => port.registers.afrl.modify(AFRL::AFRL5.val(af as u32)), + 0b0110 => port.registers.afrl.modify(AFRL::AFRL6.val(af as u32)), + 0b0111 => port.registers.afrl.modify(AFRL::AFRL7.val(af as u32)), + 0b1000 => port.registers.afrh.modify(AFRH::AFRH8.val(af as u32)), + 0b1001 => port.registers.afrh.modify(AFRH::AFRH9.val(af as u32)), + 0b1010 => port.registers.afrh.modify(AFRH::AFRH10.val(af as u32)), + 0b1011 => port.registers.afrh.modify(AFRH::AFRH11.val(af as u32)), + 0b1100 => port.registers.afrh.modify(AFRH::AFRH12.val(af as u32)), + 0b1101 => port.registers.afrh.modify(AFRH::AFRH13.val(af as u32)), + 0b1110 => port.registers.afrh.modify(AFRH::AFRH14.val(af as u32)), + 0b1111 => port.registers.afrh.modify(AFRH::AFRH15.val(af as u32)), + _ => {} + } + } + + pub fn get_pinid(&self) -> PinId { + self.pinid + } + + pub unsafe fn enable_interrupt(&'static self) { + let exti_line_id = LineId::from_u8(self.pinid.get_pin_number()).unwrap(); + + self.exti.associate_line_gpiopin(exti_line_id, self); + } + + pub fn set_exti_lineid(&self, lineid: exti::LineId) { + self.exti_lineid.set(lineid); + } + + fn set_mode_output_pushpull(&self) { + let port = self.ports_ref.unwrap_or_panic().get_port(self.pinid); // Unwrap fail = + + match self.pinid.get_pin_number() { + 0b0000 => port.registers.otyper.modify(OTYPER::OT0::CLEAR), + 0b0001 => port.registers.otyper.modify(OTYPER::OT1::CLEAR), + 0b0010 => port.registers.otyper.modify(OTYPER::OT2::CLEAR), + 0b0011 => port.registers.otyper.modify(OTYPER::OT3::CLEAR), + 0b0100 => port.registers.otyper.modify(OTYPER::OT4::CLEAR), + 0b0101 => port.registers.otyper.modify(OTYPER::OT5::CLEAR), + 0b0110 => port.registers.otyper.modify(OTYPER::OT6::CLEAR), + 0b0111 => port.registers.otyper.modify(OTYPER::OT7::CLEAR), + 0b1000 => port.registers.otyper.modify(OTYPER::OT8::CLEAR), + 0b1001 => port.registers.otyper.modify(OTYPER::OT9::CLEAR), + 0b1010 => port.registers.otyper.modify(OTYPER::OT10::CLEAR), + 0b1011 => port.registers.otyper.modify(OTYPER::OT11::CLEAR), + 0b1100 => port.registers.otyper.modify(OTYPER::OT12::CLEAR), + 0b1101 => port.registers.otyper.modify(OTYPER::OT13::CLEAR), + 0b1110 => port.registers.otyper.modify(OTYPER::OT14::CLEAR), + 0b1111 => port.registers.otyper.modify(OTYPER::OT15::CLEAR), + _ => {} + } + } + + pub fn set_speed(&self) { + let port = self.ports_ref.unwrap_or_panic().get_port(self.pinid); // Unwrap fail = + + match self.pinid.get_pin_number() { + 0b0000 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR0.val(0b11)), + 0b0001 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR1.val(0b11)), + 0b0010 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR2.val(0b11)), + 0b0011 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR3.val(0b11)), + 0b0100 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR4.val(0b11)), + 0b0101 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR5.val(0b11)), + 0b0110 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR6.val(0b11)), + 0b0111 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR7.val(0b11)), + 0b1000 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR8.val(0b11)), + 0b1001 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR9.val(0b11)), + 0b1010 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR10.val(0b11)), + 0b1011 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR11.val(0b11)), + 0b1100 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR12.val(0b11)), + 0b1101 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR13.val(0b11)), + 0b1110 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR14.val(0b11)), + 0b1111 => port.registers.ospeedr.modify(OSPEEDR::OSPEEDR15.val(0b11)), + _ => {} + } + } + + pub fn set_mode_output_opendrain(&self) { + let port = self.ports_ref.unwrap_or_panic().get_port(self.pinid); // Unwrap fail = + + match self.pinid.get_pin_number() { + 0b0000 => port.registers.otyper.modify(OTYPER::OT0::SET), + 0b0001 => port.registers.otyper.modify(OTYPER::OT1::SET), + 0b0010 => port.registers.otyper.modify(OTYPER::OT2::SET), + 0b0011 => port.registers.otyper.modify(OTYPER::OT3::SET), + 0b0100 => port.registers.otyper.modify(OTYPER::OT4::SET), + 0b0101 => port.registers.otyper.modify(OTYPER::OT5::SET), + 0b0110 => port.registers.otyper.modify(OTYPER::OT6::SET), + 0b0111 => port.registers.otyper.modify(OTYPER::OT7::SET), + 0b1000 => port.registers.otyper.modify(OTYPER::OT8::SET), + 0b1001 => port.registers.otyper.modify(OTYPER::OT9::SET), + 0b1010 => port.registers.otyper.modify(OTYPER::OT10::SET), + 0b1011 => port.registers.otyper.modify(OTYPER::OT11::SET), + 0b1100 => port.registers.otyper.modify(OTYPER::OT12::SET), + 0b1101 => port.registers.otyper.modify(OTYPER::OT13::SET), + 0b1110 => port.registers.otyper.modify(OTYPER::OT14::SET), + 0b1111 => port.registers.otyper.modify(OTYPER::OT15::SET), + _ => {} + } + } + + fn get_pullup_pulldown(&self) -> PullUpPullDown { + let port = self.ports_ref.unwrap_or_panic().get_port(self.pinid); // Unwrap fail = + + let val = match self.pinid.get_pin_number() { + 0b0000 => port.registers.pupdr.read(PUPDR::PUPDR0), + 0b0001 => port.registers.pupdr.read(PUPDR::PUPDR1), + 0b0010 => port.registers.pupdr.read(PUPDR::PUPDR2), + 0b0011 => port.registers.pupdr.read(PUPDR::PUPDR3), + 0b0100 => port.registers.pupdr.read(PUPDR::PUPDR4), + 0b0101 => port.registers.pupdr.read(PUPDR::PUPDR5), + 0b0110 => port.registers.pupdr.read(PUPDR::PUPDR6), + 0b0111 => port.registers.pupdr.read(PUPDR::PUPDR7), + 0b1000 => port.registers.pupdr.read(PUPDR::PUPDR8), + 0b1001 => port.registers.pupdr.read(PUPDR::PUPDR9), + 0b1010 => port.registers.pupdr.read(PUPDR::PUPDR10), + 0b1011 => port.registers.pupdr.read(PUPDR::PUPDR11), + 0b1100 => port.registers.pupdr.read(PUPDR::PUPDR12), + 0b1101 => port.registers.pupdr.read(PUPDR::PUPDR13), + 0b1110 => port.registers.pupdr.read(PUPDR::PUPDR14), + 0b1111 => port.registers.pupdr.read(PUPDR::PUPDR15), + _ => 0, + }; + + PullUpPullDown::from_u32(val).unwrap_or(PullUpPullDown::NoPullUpPullDown) + } + + fn set_pullup_pulldown(&self, pupd: PullUpPullDown) { + let port = self.ports_ref.unwrap_or_panic().get_port(self.pinid); // Unwrap fail = + + match self.pinid.get_pin_number() { + 0b0000 => port.registers.pupdr.modify(PUPDR::PUPDR0.val(pupd as u32)), + 0b0001 => port.registers.pupdr.modify(PUPDR::PUPDR1.val(pupd as u32)), + 0b0010 => port.registers.pupdr.modify(PUPDR::PUPDR2.val(pupd as u32)), + 0b0011 => port.registers.pupdr.modify(PUPDR::PUPDR3.val(pupd as u32)), + 0b0100 => port.registers.pupdr.modify(PUPDR::PUPDR4.val(pupd as u32)), + 0b0101 => port.registers.pupdr.modify(PUPDR::PUPDR5.val(pupd as u32)), + 0b0110 => port.registers.pupdr.modify(PUPDR::PUPDR6.val(pupd as u32)), + 0b0111 => port.registers.pupdr.modify(PUPDR::PUPDR7.val(pupd as u32)), + 0b1000 => port.registers.pupdr.modify(PUPDR::PUPDR8.val(pupd as u32)), + 0b1001 => port.registers.pupdr.modify(PUPDR::PUPDR9.val(pupd as u32)), + 0b1010 => port.registers.pupdr.modify(PUPDR::PUPDR10.val(pupd as u32)), + 0b1011 => port.registers.pupdr.modify(PUPDR::PUPDR11.val(pupd as u32)), + 0b1100 => port.registers.pupdr.modify(PUPDR::PUPDR12.val(pupd as u32)), + 0b1101 => port.registers.pupdr.modify(PUPDR::PUPDR13.val(pupd as u32)), + 0b1110 => port.registers.pupdr.modify(PUPDR::PUPDR14.val(pupd as u32)), + 0b1111 => port.registers.pupdr.modify(PUPDR::PUPDR15.val(pupd as u32)), + _ => {} + } + } + + fn set_output_high(&self) { + let port = self.ports_ref.unwrap_or_panic().get_port(self.pinid); // Unwrap fail = + + match self.pinid.get_pin_number() { + 0b0000 => port.registers.bsrr.write(BSRR::BS0::SET), + 0b0001 => port.registers.bsrr.write(BSRR::BS1::SET), + 0b0010 => port.registers.bsrr.write(BSRR::BS2::SET), + 0b0011 => port.registers.bsrr.write(BSRR::BS3::SET), + 0b0100 => port.registers.bsrr.write(BSRR::BS4::SET), + 0b0101 => port.registers.bsrr.write(BSRR::BS5::SET), + 0b0110 => port.registers.bsrr.write(BSRR::BS6::SET), + 0b0111 => port.registers.bsrr.write(BSRR::BS7::SET), + 0b1000 => port.registers.bsrr.write(BSRR::BS8::SET), + 0b1001 => port.registers.bsrr.write(BSRR::BS9::SET), + 0b1010 => port.registers.bsrr.write(BSRR::BS10::SET), + 0b1011 => port.registers.bsrr.write(BSRR::BS11::SET), + 0b1100 => port.registers.bsrr.write(BSRR::BS12::SET), + 0b1101 => port.registers.bsrr.write(BSRR::BS13::SET), + 0b1110 => port.registers.bsrr.write(BSRR::BS14::SET), + 0b1111 => port.registers.bsrr.write(BSRR::BS15::SET), + _ => {} + } + } + + fn set_output_low(&self) { + let port = self.ports_ref.unwrap_or_panic().get_port(self.pinid); // Unwrap fail = + + match self.pinid.get_pin_number() { + 0b0000 => port.registers.bsrr.write(BSRR::BR0::SET), + 0b0001 => port.registers.bsrr.write(BSRR::BR1::SET), + 0b0010 => port.registers.bsrr.write(BSRR::BR2::SET), + 0b0011 => port.registers.bsrr.write(BSRR::BR3::SET), + 0b0100 => port.registers.bsrr.write(BSRR::BR4::SET), + 0b0101 => port.registers.bsrr.write(BSRR::BR5::SET), + 0b0110 => port.registers.bsrr.write(BSRR::BR6::SET), + 0b0111 => port.registers.bsrr.write(BSRR::BR7::SET), + 0b1000 => port.registers.bsrr.write(BSRR::BR8::SET), + 0b1001 => port.registers.bsrr.write(BSRR::BR9::SET), + 0b1010 => port.registers.bsrr.write(BSRR::BR10::SET), + 0b1011 => port.registers.bsrr.write(BSRR::BR11::SET), + 0b1100 => port.registers.bsrr.write(BSRR::BR12::SET), + 0b1101 => port.registers.bsrr.write(BSRR::BR13::SET), + 0b1110 => port.registers.bsrr.write(BSRR::BR14::SET), + 0b1111 => port.registers.bsrr.write(BSRR::BR15::SET), + _ => {} + } + } + + fn is_output_high(&self) -> bool { + let port = self.ports_ref.unwrap_or_panic().get_port(self.pinid); // Unwrap fail = + + match self.pinid.get_pin_number() { + 0b0000 => port.registers.odr.is_set(ODR::ODR0), + 0b0001 => port.registers.odr.is_set(ODR::ODR1), + 0b0010 => port.registers.odr.is_set(ODR::ODR2), + 0b0011 => port.registers.odr.is_set(ODR::ODR3), + 0b0100 => port.registers.odr.is_set(ODR::ODR4), + 0b0101 => port.registers.odr.is_set(ODR::ODR5), + 0b0110 => port.registers.odr.is_set(ODR::ODR6), + 0b0111 => port.registers.odr.is_set(ODR::ODR7), + 0b1000 => port.registers.odr.is_set(ODR::ODR8), + 0b1001 => port.registers.odr.is_set(ODR::ODR9), + 0b1010 => port.registers.odr.is_set(ODR::ODR10), + 0b1011 => port.registers.odr.is_set(ODR::ODR11), + 0b1100 => port.registers.odr.is_set(ODR::ODR12), + 0b1101 => port.registers.odr.is_set(ODR::ODR13), + 0b1110 => port.registers.odr.is_set(ODR::ODR14), + 0b1111 => port.registers.odr.is_set(ODR::ODR15), + _ => false, + } + } + + fn toggle_output(&self) -> bool { + if self.is_output_high() { + self.set_output_low(); + false + } else { + self.set_output_high(); + true + } + } + + fn read_input(&self) -> bool { + let port = self.ports_ref.unwrap_or_panic().get_port(self.pinid); // Unwrap fail = + + match self.pinid.get_pin_number() { + 0b0000 => port.registers.idr.is_set(IDR::IDR0), + 0b0001 => port.registers.idr.is_set(IDR::IDR1), + 0b0010 => port.registers.idr.is_set(IDR::IDR2), + 0b0011 => port.registers.idr.is_set(IDR::IDR3), + 0b0100 => port.registers.idr.is_set(IDR::IDR4), + 0b0101 => port.registers.idr.is_set(IDR::IDR5), + 0b0110 => port.registers.idr.is_set(IDR::IDR6), + 0b0111 => port.registers.idr.is_set(IDR::IDR7), + 0b1000 => port.registers.idr.is_set(IDR::IDR8), + 0b1001 => port.registers.idr.is_set(IDR::IDR9), + 0b1010 => port.registers.idr.is_set(IDR::IDR10), + 0b1011 => port.registers.idr.is_set(IDR::IDR11), + 0b1100 => port.registers.idr.is_set(IDR::IDR12), + 0b1101 => port.registers.idr.is_set(IDR::IDR13), + 0b1110 => port.registers.idr.is_set(IDR::IDR14), + 0b1111 => port.registers.idr.is_set(IDR::IDR15), + _ => false, + } + } +} + +impl hil::gpio::Configure for Pin<'_> { + /// Output mode default is push-pull + fn make_output(&self) -> hil::gpio::Configuration { + self.set_mode(Mode::GeneralPurposeOutputMode); + self.set_mode_output_pushpull(); + hil::gpio::Configuration::Output + } + + /// Input mode default is no internal pull-up, no pull-down (i.e., + /// floating). Also upon setting the mode as input, the internal schmitt + /// trigger is automatically activated. Schmitt trigger is deactivated in + /// AnalogMode. + fn make_input(&self) -> hil::gpio::Configuration { + self.set_mode(Mode::Input); + hil::gpio::Configuration::Input + } + + /// According to AN4899, Section 6.1, setting to AnalogMode, disables + /// internal schmitt trigger. We do not disable clock to the GPIO port, + /// because there could be other pins active on the port. + fn deactivate_to_low_power(&self) { + self.set_mode(Mode::AnalogMode); + } + + fn disable_output(&self) -> hil::gpio::Configuration { + self.set_mode(Mode::AnalogMode); + hil::gpio::Configuration::LowPower + } + + fn disable_input(&self) -> hil::gpio::Configuration { + self.set_mode(Mode::AnalogMode); + hil::gpio::Configuration::LowPower + } + + fn set_floating_state(&self, mode: hil::gpio::FloatingState) { + match mode { + hil::gpio::FloatingState::PullUp => self.set_pullup_pulldown(PullUpPullDown::PullUp), + hil::gpio::FloatingState::PullDown => { + self.set_pullup_pulldown(PullUpPullDown::PullDown) + } + hil::gpio::FloatingState::PullNone => { + self.set_pullup_pulldown(PullUpPullDown::NoPullUpPullDown) + } + } + } + + fn floating_state(&self) -> hil::gpio::FloatingState { + match self.get_pullup_pulldown() { + PullUpPullDown::PullUp => hil::gpio::FloatingState::PullUp, + PullUpPullDown::PullDown => hil::gpio::FloatingState::PullDown, + PullUpPullDown::NoPullUpPullDown => hil::gpio::FloatingState::PullNone, + } + } + + fn configuration(&self) -> hil::gpio::Configuration { + match self.get_mode() { + Mode::Input => hil::gpio::Configuration::Input, + Mode::GeneralPurposeOutputMode => hil::gpio::Configuration::Output, + Mode::AnalogMode => hil::gpio::Configuration::LowPower, + Mode::AlternateFunctionMode => hil::gpio::Configuration::Function, + } + } + + fn is_input(&self) -> bool { + self.get_mode() == Mode::Input + } + + fn is_output(&self) -> bool { + self.get_mode() == Mode::GeneralPurposeOutputMode + } +} + +impl hil::gpio::Output for Pin<'_> { + fn set(&self) { + self.set_output_high(); + } + + fn clear(&self) { + self.set_output_low(); + } + + fn toggle(&self) -> bool { + self.toggle_output() + } +} + +impl hil::gpio::Input for Pin<'_> { + fn read(&self) -> bool { + self.read_input() + } +} + +impl<'a> hil::gpio::Interrupt<'a> for Pin<'a> { + fn enable_interrupts(&self, mode: hil::gpio::InterruptEdge) { + unsafe { + with_interrupts_disabled(|| { + self.exti_lineid.map(|lineid| { + let l = lineid; + + // disable the interrupt + self.exti.mask_interrupt(l); + self.exti.clear_pending(l); + + match mode { + hil::gpio::InterruptEdge::EitherEdge => { + self.exti.select_rising_trigger(l); + self.exti.select_falling_trigger(l); + } + hil::gpio::InterruptEdge::RisingEdge => { + self.exti.select_rising_trigger(l); + self.exti.deselect_falling_trigger(l); + } + hil::gpio::InterruptEdge::FallingEdge => { + self.exti.deselect_rising_trigger(l); + self.exti.select_falling_trigger(l); + } + } + + self.exti.unmask_interrupt(l); + }); + }); + } + } + + fn disable_interrupts(&self) { + unsafe { + with_interrupts_disabled(|| { + self.exti_lineid.map(|lineid| { + let l = lineid; + self.exti.mask_interrupt(l); + self.exti.clear_pending(l); + }); + }); + } + } + + fn set_client(&self, client: &'a dyn hil::gpio::Client) { + self.client.set(client); + } + + fn is_pending(&self) -> bool { + self.exti_lineid + .map_or(false, |lineid| self.exti.is_pending(lineid)) + } +} diff --git a/chips/stm32l4xx/src/lib.rs b/chips/stm32l4xx/src/lib.rs new file mode 100644 index 0000000000..0ce4d1240e --- /dev/null +++ b/chips/stm32l4xx/src/lib.rs @@ -0,0 +1,64 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +//! Peripheral implementations for the STM32L4xx MCU. +//! +//! STM32L476RG: + +#![no_std] + +pub mod chip; +pub mod chip_specific; +pub mod nvic; + +// Clocks +pub mod clocks; + +// Peripherials +pub mod exti; +pub mod flash; +pub mod gpio; +pub mod pwr; +pub mod rcc; +pub mod syscfg; +pub mod usart; + +use cortexm4f::{initialize_ram_jump_to_main, unhandled_interrupt, CortexM4F, CortexMVariant}; + +extern "C" { + // _estack is not really a function, but it makes the types work + // You should never actually invoke it!! + fn _estack(); +} + +#[cfg_attr( + all(target_arch = "arm", target_os = "none"), + link_section = ".vectors" +)] +// used Ensures that the symbol is kept until the final binary +#[cfg_attr(all(target_arch = "arm", target_os = "none"), used)] +pub static BASE_VECTORS: [unsafe extern "C" fn(); 16] = [ + _estack, + initialize_ram_jump_to_main, + unhandled_interrupt, // NMI + CortexM4F::HARD_FAULT_HANDLER, // Hard Fault + unhandled_interrupt, // MemManage + unhandled_interrupt, // BusFault + unhandled_interrupt, // UsageFault + unhandled_interrupt, + unhandled_interrupt, + unhandled_interrupt, + unhandled_interrupt, + CortexM4F::SVC_HANDLER, // SVC + unhandled_interrupt, // DebugMon + unhandled_interrupt, + unhandled_interrupt, // PendSV + CortexM4F::SYSTICK_HANDLER, // SysTick +]; + +pub unsafe fn init() { + cortexm4f::nvic::disable_all(); + cortexm4f::nvic::clear_all_pending(); + cortexm4f::nvic::enable_all(); +} diff --git a/chips/stm32l4xx/src/nvic.rs b/chips/stm32l4xx/src/nvic.rs new file mode 100644 index 0000000000..e9bf6e6ac9 --- /dev/null +++ b/chips/stm32l4xx/src/nvic.rs @@ -0,0 +1,90 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +//! STM32L47x/L48x/L49x/L4Ax vector table + +#![allow(non_upper_case_globals)] + +pub const WWDG: u32 = 0; +pub const PVD_PVM: u32 = 1; +pub const TAMP_STAMP: u32 = 2; +pub const RTC_WKUP: u32 = 3; +pub const FLASH: u32 = 4; +pub const RCC: u32 = 5; +pub const EXTI0: u32 = 6; +pub const EXTI1: u32 = 7; +pub const EXTI2: u32 = 8; +pub const EXTI3: u32 = 9; +pub const EXTI4: u32 = 10; +pub const DMA1_CHANNEL1: u32 = 11; +pub const DMA1_CHANNEL2: u32 = 12; +pub const DMA1_CHANNEL3: u32 = 13; +pub const DMA1_CHANNEL4: u32 = 14; +pub const DMA1_CHANNEL5: u32 = 15; +pub const DMA1_CHANNEL6: u32 = 16; +pub const DMA1_CHANNEL7: u32 = 17; +pub const ADC1_2: u32 = 18; +pub const CAN1_TX: u32 = 19; +pub const CAN1_RX0: u32 = 20; +pub const CAN1_RX1: u32 = 21; +pub const CAN1_SCE: u32 = 22; +pub const EXTI9_5: u32 = 23; +pub const TIM1_BRK_TIM15: u32 = 24; +pub const TIM1_UP_TIM16: u32 = 25; +pub const TIM1_TRG_COM_TIM17: u32 = 26; +pub const TIM1_CC: u32 = 27; +pub const TIM2: u32 = 28; +pub const TIM3: u32 = 29; +pub const TIM4: u32 = 30; +pub const I2C1_EV: u32 = 31; +pub const I2C1_ER: u32 = 32; +pub const I2C2_EV: u32 = 33; +pub const I2C2_ER: u32 = 34; +pub const SPI1: u32 = 35; +pub const SPI2: u32 = 36; +pub const USART1: u32 = 37; +pub const USART2: u32 = 38; +pub const USART3: u32 = 39; +pub const EXTI15_10: u32 = 40; +pub const RTC_ALARM: u32 = 41; +pub const DFSDM1_FLT3: u32 = 42; +pub const TIM8_BRK: u32 = 43; +pub const TIM8_UP: u32 = 44; +pub const TIM8_TRG_COM: u32 = 45; +pub const TIM8_CC: u32 = 46; +pub const ADC3: u32 = 47; +pub const FMC: u32 = 48; +pub const SDMMC1: u32 = 49; +pub const TIM5: u32 = 50; +pub const SPI3: u32 = 51; +pub const UART4: u32 = 52; +pub const UART5: u32 = 53; +pub const TIM6_DAC: u32 = 54; +pub const TIM7: u32 = 55; +pub const DMA2_CHANNEL1: u32 = 56; +pub const DMA2_CHANNEL2: u32 = 57; +pub const DMA2_CHANNEL3: u32 = 58; +pub const DMA2_CHANNEL4: u32 = 59; +pub const DMA2_CHANNEL5: u32 = 60; +pub const DFSDM1_FLT0: u32 = 61; +pub const DFSDM1_FLT1: u32 = 62; +pub const DFSDM1_FLT2: u32 = 63; +pub const COMP: u32 = 64; +pub const LPTIM1: u32 = 65; +pub const LPTIM2: u32 = 66; +pub const OTG_FS: u32 = 67; +pub const DMA2_CHANNEL6: u32 = 68; +pub const DMA2_CHANNEL7: u32 = 69; +pub const LPUART1: u32 = 70; +pub const QUADSPI: u32 = 71; +pub const I2C3_EV: u32 = 72; +pub const I2C3_ER: u32 = 73; +pub const SAI1: u32 = 74; +pub const SAI2: u32 = 75; +pub const SWPMI1: u32 = 76; +pub const TSC: u32 = 77; +pub const LCD: u32 = 78; +// 79 is reserved in STM32L476 +pub const RNG: u32 = 80; +pub const FPU: u32 = 81; diff --git a/chips/stm32l4xx/src/pwr.rs b/chips/stm32l4xx/src/pwr.rs new file mode 100644 index 0000000000..b25121e8c5 --- /dev/null +++ b/chips/stm32l4xx/src/pwr.rs @@ -0,0 +1,74 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +use kernel::utilities::registers::interfaces::Readable; +use kernel::utilities::registers::{register_bitfields, register_structs, ReadOnly, ReadWrite}; +use kernel::utilities::StaticRef; + +register_structs! { + /// Power control + PwrRegisters { + /// Power control register 1 + (0x000 => cr1: ReadWrite), + (0x004 => _reserved0), + /// Power status register 2 + (0x014 => sr2: ReadOnly), + (0x018 => @END), + } +} +register_bitfields![u32, + // PWR control register 1 (CR1) — STM32L4xx + CR1 [ + /// Backup domain write protection disable + DBP OFFSET(8) NUMBITS(1) [], + /// Voltage scaling range selection (bits 10:9) + /// 00: Forbidden, 01: Range1, 10: Range2, 11: Forbidden + VOS OFFSET(9) NUMBITS(2) [ + Range1 = 0b01, + Range2 = 0b10 + ] + ], + + // PWR status register 2 (SR2) — STM32L4xx + SR2 [ + /// Voltage scaling flag (1: VOS change ongoing) + VOSF OFFSET(10) NUMBITS(1) [] + ], +]; +const PWR_BASE: StaticRef = + unsafe { StaticRef::new(0x40007000 as *const PwrRegisters) }; + +pub struct Pwr { + registers: StaticRef, +} + +impl Pwr { + pub fn new() -> Self { + let pwr = Self { + registers: PWR_BASE, + }; + pwr + } + + pub(crate) fn get_vos(&self) -> VOS { + match self.registers.cr1.read(CR1::VOS) { + 1 => VOS::Range1, + 2 => VOS::Range2, + _ => todo!(), + } + } + + pub(crate) fn is_vos_ready(&self) -> bool { + match self.registers.sr2.read(SR2::VOSF) { + 0 => true, + _ => false, + } + } +} + +#[derive(Copy, Clone, Debug, PartialEq)] +pub(crate) enum VOS { + Range1 = 1, + Range2 = 2, +} diff --git a/chips/stm32l4xx/src/rcc.rs b/chips/stm32l4xx/src/rcc.rs new file mode 100644 index 0000000000..cbc550d35f --- /dev/null +++ b/chips/stm32l4xx/src/rcc.rs @@ -0,0 +1,1481 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +use kernel::utilities::registers::interfaces::{ReadWriteable, Readable}; +use kernel::utilities::registers::{register_bitfields, ReadWrite}; +use kernel::utilities::StaticRef; + +/// Reset and clock control +#[repr(C)] +struct RccRegisters { + /// clock control register + cr: ReadWrite, + /// internal clock sources calibration register + icscr: ReadWrite, + /// clock configuration register + cfgr: ReadWrite, + /// system PLL configuration register + pllcfgr: ReadWrite, + /// PLL SAI1 configuration register + pllsai1cfgr: ReadWrite, + /// PLL SAI2 configuration register + pllsai2cfgr: ReadWrite, + /// clock interrupt enable register + cier: ReadWrite, + /// clock interrupt flag register + cifr: ReadWrite, + /// clock interrupt clear register + cicr: ReadWrite, + _reserved0: [u8; 4], + /// AHB1 peripheral reset register + ahb1rstr: ReadWrite, + /// AHB2 peripheral reset register + ahb2rstr: ReadWrite, + /// AHB3 peripheral reset register + ahb3rstr: ReadWrite, + _reserved1: [u8; 4], + /// APB1 peripheral reset register 1 + apb1rstr1: ReadWrite, + /// APB1 peripheral reset register 2 + apb1rstr2: ReadWrite, + /// APB2 peripheral reset register + apb2rstr: ReadWrite, + _reserved2: [u8; 4], + /// AHB1 peripheral clock enable register + ahb1enr: ReadWrite, + /// AHB2 peripheral clock enable register + ahb2enr: ReadWrite, + /// AHB3 peripheral clock enable register + ahb3enr: ReadWrite, + _reserved3: [u8; 4], + /// APB1 peripheral clock enable register 1 + apb1enr1: ReadWrite, + /// APB1 peripheral clock enable register 2 + apb1enr2: ReadWrite, + /// APB2 peripheral clock enable register + apb2enr: ReadWrite, + _reserved4: [u8; 4], + /// AHB1 peripheral clocks enable in sleep and stop modes register + ahb1smenr: ReadWrite, + /// AHB2 peripheral clocks enable in sleep and stop modes register + ahb2smenr: ReadWrite, + /// AHB3 peripheral clocks enable in sleep and stop modes register + ahb3smenr: ReadWrite, + _reserved5: [u8; 4], + /// APB1 peripheral clocks enable in sleep and stop modes register 1 + apb1smenr1: ReadWrite, + /// APB1 peripheral clocks enable in sleep and stop modes register 2 + apb1smenr2: ReadWrite, + /// APB2 peripheral clocks enable in sleep and stop modes register + apb2smenr: ReadWrite, + _reserved6: [u8; 4], + /// peripherals independent clock configuration register + ccipr: ReadWrite, + _reserved7: [u8; 4], + /// backup domain control register + bdcr: ReadWrite, + /// clock control & status register + csr: ReadWrite, +} + +register_bitfields![u32, + CR [ + /// SAI2 PLL clock ready flag + PLLSAI2RDY OFFSET(29) NUMBITS(1) [], + /// SAI2 PLL enable + PLLSAI2ON OFFSET(28) NUMBITS(1) [], + /// SAI1 PLL clock ready flag + PLLSAI1RDY OFFSET(27) NUMBITS(1) [], + /// SAI1 PLL enable + PLLSAI1ON OFFSET(26) NUMBITS(1) [], + /// Main PLL clock ready flag + PLLRDY OFFSET(25) NUMBITS(1) [], + /// Main PLL enable + PLLON OFFSET(24) NUMBITS(1) [], + /// Clock security system enable + CSSON OFFSET(19) NUMBITS(1) [], + /// HSE crystal oscillator bypass + HSEBYP OFFSET(18) NUMBITS(1) [], + /// HSE clock ready flag + HSERDY OFFSET(17) NUMBITS(1) [], + /// HSE clock enable + HSEON OFFSET(16) NUMBITS(1) [], + /// HSI automatic start from Stop + HSIASFS OFFSET(11) NUMBITS(1) [], + /// HSI clock ready flag + HSIRDY OFFSET(10) NUMBITS(1) [], + /// HSI always enable for peripheral kernels + HSIKERON OFFSET(9) NUMBITS(1) [], + /// HSI clock enable + HSION OFFSET(8) NUMBITS(1) [], + /// MSI clock ranges + MSIRANGE OFFSET(4) NUMBITS(4) [ + Range100kHz = 0, + Range200kHz = 1, + Range400kHz = 2, + Range800kHz = 3, + Range1MHz = 4, + Range2MHz = 5, + Range4MHz = 6, + Range8MHz = 7, + Range16MHz = 8, + Range24MHz = 9, + Range32MHz = 10, + Range48MHz = 11 + ], + /// MSI clock range selection + MSIRGSEL OFFSET(3) NUMBITS(1) [], + /// MSI clock PLL enable + MSIPLLEN OFFSET(2) NUMBITS(1) [], + /// MSI clock ready flag + MSIRDY OFFSET(1) NUMBITS(1) [], + /// MSI clock enable + MSION OFFSET(0) NUMBITS(1) [] + ], + ICSCR [ + /// HSI clock trimming + HSITRIM OFFSET(24) NUMBITS(7) [], + /// HSI clock calibration + HSICAL OFFSET(16) NUMBITS(8) [], + /// MSI clock trimming + MSITRIM OFFSET(8) NUMBITS(8) [], + /// MSI clock calibration + MSICAL OFFSET(0) NUMBITS(8) [] + ], + CFGR [ + /// Microcontroller clock output prescaler + MCOPRE OFFSET(28) NUMBITS(3) [ + Div1 = 0, + Div2 = 1, + Div4 = 2, + Div8 = 3, + Div16 = 4 + ], + /// Microcontroller clock output + MCOSEL OFFSET(24) NUMBITS(4) [ + NoClock = 0, + SYSCLK = 1, + MSI = 2, + HSI16 = 3, + HSE = 4, + PLL = 5, + LSI = 6, + LSE = 7, + HSI48 = 8 + ], + /// Wakeup from Stop and CSS backup clock selection + STOPWUCK OFFSET(15) NUMBITS(1) [ + MSI = 0, + HSI16 = 1 + ], + /// APB high-speed prescaler (APB2) + PPRE2 OFFSET(11) NUMBITS(3) [ + Div1 = 0, + Div2 = 4, + Div4 = 5, + Div8 = 6, + Div16 = 7 + ], + /// APB low-speed prescaler (APB1) + PPRE1 OFFSET(8) NUMBITS(3) [ + Div1 = 0, + Div2 = 4, + Div4 = 5, + Div8 = 6, + Div16 = 7 + ], + /// AHB prescaler + HPRE OFFSET(4) NUMBITS(4) [ + Div1 = 0, + Div2 = 8, + Div4 = 9, + Div8 = 10, + Div16 = 11, + Div64 = 12, + Div128 = 13, + Div256 = 14, + Div512 = 15 + ], + /// System clock switch status + SWS OFFSET(2) NUMBITS(2) [ + MSI = 0, + HSI16 = 1, + HSE = 2, + PLL = 3 + ], + /// System clock switch + SW OFFSET(0) NUMBITS(2) [ + MSI = 0, + HSI16 = 1, + HSE = 2, + PLL = 3 + ] + ], + PLLCFGR [ + /// Main PLL division factor for PLLSAI2CLK + PLLPDIV OFFSET(27) NUMBITS(5) [], + /// Main PLL PLLCLK output enable + PLLR OFFSET(25) NUMBITS(2) [ + Div2 = 0, + Div4 = 1, + Div6 = 2, + Div8 = 3 + ], + /// Main PLL PLLCLK output enable + PLLREN OFFSET(24) NUMBITS(1) [], + /// Main PLL division factor for PLLCLK (system clock) + PLLQ OFFSET(21) NUMBITS(2) [ + Div2 = 0, + Div4 = 1, + Div6 = 2, + Div8 = 3 + ], + /// Main PLL PLLQCLK output enable + PLLQEN OFFSET(20) NUMBITS(1) [], + /// Main PLL division factor for PLLSAI3CLK (SAI1 and SAI2 clock) + PLLP OFFSET(17) NUMBITS(1) [ + Div7 = 0, + Div17 = 1 + ], + /// Main PLL PLLSAI3CLK output enable + PLLPEN OFFSET(16) NUMBITS(1) [], + /// Main PLL multiplication factor for VCO + PLLN OFFSET(8) NUMBITS(7) [], + /// Division factor for the main PLL and audio PLL input clock + PLLM OFFSET(4) NUMBITS(3) [ + Div1 = 0, + Div2 = 1, + Div3 = 2, + Div4 = 3, + Div5 = 4, + Div6 = 5, + Div7 = 6, + Div8 = 7 + ], + /// Main PLL, PLLSAI1 and PLLSAI2 entry clock source + PLLSRC OFFSET(0) NUMBITS(2) [ + NoClock = 0, + MSI = 1, + HSI = 2, + HSE = 3 + ] + ], + PLLSAI1CFGR [ + /// PLLSAI1 division factor for PLLADC1CLK (ADC clock) + PLLSAI1R OFFSET(25) NUMBITS(2) [ + Div2 = 0, + Div4 = 1, + Div6 = 2, + Div8 = 3 + ], + /// PLLSAI1 PLLADC1CLK output enable + PLLSAI1REN OFFSET(24) NUMBITS(1) [], + /// SAI1PLL division factor for PLLUSB2CLK (48 MHz clock) + PLLSAI1Q OFFSET(21) NUMBITS(2) [ + Div2 = 0, + Div4 = 1, + Div6 = 2, + Div8 = 3 + ], + /// SAI1PLL PLLUSB2CLK output enable + PLLSAI1QEN OFFSET(20) NUMBITS(1) [], + /// SAI1PLL division factor for PLLSAI1CLK (SAI1 or SAI2 clock) + PLLSAI1P OFFSET(17) NUMBITS(1) [ + Div7 = 0, + Div17 = 1 + ], + /// SAI1PLL PLLSAI1CLK output enable + PLLSAI1PEN OFFSET(16) NUMBITS(1) [], + /// SAI1PLL multiplication factor for VCO + PLLSAI1N OFFSET(8) NUMBITS(7) [] + ], + PLLSAI2CFGR [ + /// PLLSAI2 division factor for PLLADC2CLK (ADC clock) + PLLSAI2R OFFSET(25) NUMBITS(2) [ + Div2 = 0, + Div4 = 1, + Div6 = 2, + Div8 = 3 + ], + /// PLLSAI2 PLLADC2CLK output enable + PLLSAI2REN OFFSET(24) NUMBITS(1) [], + /// SAI2PLL division factor for PLLSAI2CLK (SAI1 or SAI2 clock) + PLLSAI2P OFFSET(17) NUMBITS(1) [ + Div7 = 0, + Div17 = 1 + ], + /// SAI2PLL PLLSAI2CLK output enable + PLLSAI2PEN OFFSET(16) NUMBITS(1) [], + /// SAI2PLL multiplication factor for VCO + PLLSAI2N OFFSET(8) NUMBITS(7) [] + ], + CIER [ + /// LSE clock security system interrupt enable + LSECSSIE OFFSET(9) NUMBITS(1) [], + /// PLL SAI2 ready interrupt enable + PLLSAI2RDYIE OFFSET(7) NUMBITS(1) [], + /// PLL SAI1 ready interrupt enable + PLLSAI1RDYIE OFFSET(6) NUMBITS(1) [], + /// PLL ready interrupt enable + PLLRDYIE OFFSET(5) NUMBITS(1) [], + /// HSE ready interrupt enable + HSERDYIE OFFSET(4) NUMBITS(1) [], + /// HSI16 ready interrupt enable + HSIRDYIE OFFSET(3) NUMBITS(1) [], + /// MSI ready interrupt enable + MSIRDYIE OFFSET(2) NUMBITS(1) [], + /// LSE ready interrupt enable + LSERDYIE OFFSET(1) NUMBITS(1) [], + /// LSI ready interrupt enable + LSIRDYIE OFFSET(0) NUMBITS(1) [] + ], + CIFR [ + /// LSE Clock security system interrupt flag + LSECSSF OFFSET(9) NUMBITS(1) [], + /// Clock security system interrupt flag + CSSF OFFSET(8) NUMBITS(1) [], + /// PLLSAI2 ready interrupt flag + PLLSAI2RDYF OFFSET(7) NUMBITS(1) [], + /// PLLSAI1 ready interrupt flag + PLLSAI1RDYF OFFSET(6) NUMBITS(1) [], + /// PLL ready interrupt flag + PLLRDYF OFFSET(5) NUMBITS(1) [], + /// HSE ready interrupt flag + HSERDYF OFFSET(4) NUMBITS(1) [], + /// HSI16 ready interrupt flag + HSIRDYF OFFSET(3) NUMBITS(1) [], + /// MSI ready interrupt flag + MSIRDYF OFFSET(2) NUMBITS(1) [], + /// LSE ready interrupt flag + LSERDYF OFFSET(1) NUMBITS(1) [], + /// LSI ready interrupt flag + LSIRDYF OFFSET(0) NUMBITS(1) [] + ], + CICR [ + /// LSE Clock security system interrupt clear + LSECSSC OFFSET(9) NUMBITS(1) [], + /// Clock security system interrupt clear + CSSC OFFSET(8) NUMBITS(1) [], + /// PLLSAI2 ready interrupt clear + PLLSAI2RDYC OFFSET(7) NUMBITS(1) [], + /// PLLSAI1 ready interrupt clear + PLLSAI1RDYC OFFSET(6) NUMBITS(1) [], + /// PLL ready interrupt clear + PLLRDYC OFFSET(5) NUMBITS(1) [], + /// HSE ready interrupt clear + HSERDYC OFFSET(4) NUMBITS(1) [], + /// HSI16 ready interrupt clear + HSIRDYC OFFSET(3) NUMBITS(1) [], + /// MSI ready interrupt clear + MSIRDYC OFFSET(2) NUMBITS(1) [], + /// LSE ready interrupt clear + LSERDYC OFFSET(1) NUMBITS(1) [], + /// LSI ready interrupt clear + LSIRDYC OFFSET(0) NUMBITS(1) [] + ], + AHB1RSTR [ + /// Touch Sensing Controller reset + TSCRST OFFSET(16) NUMBITS(1) [], + /// CRC reset + CRCRST OFFSET(12) NUMBITS(1) [], + /// Flash memory interface reset + FLASHRST OFFSET(8) NUMBITS(1) [], + /// DMA2 reset + DMA2RST OFFSET(1) NUMBITS(1) [], + /// DMA1 reset + DMA1RST OFFSET(0) NUMBITS(1) [] + ], + AHB2RSTR [ + /// Random number generator reset + RNGRST OFFSET(18) NUMBITS(1) [], + /// AES hardware accelerator reset + AESRST OFFSET(16) NUMBITS(1) [], + /// ADC reset + ADCRST OFFSET(13) NUMBITS(1) [], + /// USB OTG FS reset + OTGFSRST OFFSET(12) NUMBITS(1) [], + /// IO port H reset + GPIOHRST OFFSET(7) NUMBITS(1) [], + /// IO port G reset + GPIOGRST OFFSET(6) NUMBITS(1) [], + /// IO port F reset + GPIOFRST OFFSET(5) NUMBITS(1) [], + /// IO port E reset + GPIOERST OFFSET(4) NUMBITS(1) [], + /// IO port D reset + GPIODRST OFFSET(3) NUMBITS(1) [], + /// IO port C reset + GPIOCRST OFFSET(2) NUMBITS(1) [], + /// IO port B reset + GPIOBRST OFFSET(1) NUMBITS(1) [], + /// IO port A reset + GPIOARST OFFSET(0) NUMBITS(1) [] + ], + AHB3RSTR [ + /// Quad SPI memory interface reset + QSPIRST OFFSET(8) NUMBITS(1) [], + /// Flexible memory controller reset + FMCRST OFFSET(0) NUMBITS(1) [] + ], + APB1RSTR1 [ + /// Low Power Timer 1 reset + LPTIM1RST OFFSET(31) NUMBITS(1) [], + /// OPAMP interface reset + OPAMPRST OFFSET(30) NUMBITS(1) [], + /// DAC1 interface reset + DAC1RST OFFSET(29) NUMBITS(1) [], + /// Power interface reset + PWRRST OFFSET(28) NUMBITS(1) [], + /// CAN1 reset + CAN1RST OFFSET(25) NUMBITS(1) [], + /// I2C3 reset + I2C3RST OFFSET(23) NUMBITS(1) [], + /// I2C2 reset + I2C2RST OFFSET(22) NUMBITS(1) [], + /// I2C1 reset + I2C1RST OFFSET(21) NUMBITS(1) [], + /// UART5 reset + UART5RST OFFSET(20) NUMBITS(1) [], + /// UART4 reset + UART4RST OFFSET(19) NUMBITS(1) [], + /// USART3 reset + USART3RST OFFSET(18) NUMBITS(1) [], + /// USART2 reset + USART2RST OFFSET(17) NUMBITS(1) [], + /// SPI3 reset + SPI3RST OFFSET(15) NUMBITS(1) [], + /// SPI2 reset + SPI2RST OFFSET(14) NUMBITS(1) [], + /// Window watchdog reset + WWDGRST OFFSET(11) NUMBITS(1) [], + /// TIM7 timer reset + TIM7RST OFFSET(5) NUMBITS(1) [], + /// TIM6 timer reset + TIM6RST OFFSET(4) NUMBITS(1) [], + /// TIM5 timer reset + TIM5RST OFFSET(3) NUMBITS(1) [], + /// TIM4 timer reset + TIM4RST OFFSET(2) NUMBITS(1) [], + /// TIM3 timer reset + TIM3RST OFFSET(1) NUMBITS(1) [], + /// TIM2 timer reset + TIM2RST OFFSET(0) NUMBITS(1) [] + ], + APB1RSTR2 [ + /// Low-power timer 2 reset + LPTIM2RST OFFSET(5) NUMBITS(1) [], + /// Single wire protocol reset + SWPMI1RST OFFSET(2) NUMBITS(1) [], + /// Low-power UART 1 reset + LPUART1RST OFFSET(0) NUMBITS(1) [] + ], + APB2RSTR [ + /// DFSDM filter reset + DFSDMRST OFFSET(24) NUMBITS(1) [], + /// Serial audio interface 2 (SAI2) reset + SAI2RST OFFSET(22) NUMBITS(1) [], + /// Serial audio interface 1 (SAI1) reset + SAI1RST OFFSET(21) NUMBITS(1) [], + /// TIM17 timer reset + TIM17RST OFFSET(18) NUMBITS(1) [], + /// TIM16 timer reset + TIM16RST OFFSET(17) NUMBITS(1) [], + /// TIM15 timer reset + TIM15RST OFFSET(16) NUMBITS(1) [], + /// USART1 reset + USART1RST OFFSET(14) NUMBITS(1) [], + /// TIM8 timer reset + TIM8RST OFFSET(13) NUMBITS(1) [], + /// SPI1 reset + SPI1RST OFFSET(12) NUMBITS(1) [], + /// TIM1 timer reset + TIM1RST OFFSET(11) NUMBITS(1) [], + /// SDMMC reset + SDMMCRST OFFSET(10) NUMBITS(1) [], + /// System configuration (SYSCFG) reset + SYSCFGRST OFFSET(0) NUMBITS(1) [] + ], + AHB1ENR [ + /// Touch Sensing Controller clock enable + TSCEN OFFSET(16) NUMBITS(1) [], + /// CRC clock enable + CRCEN OFFSET(12) NUMBITS(1) [], + /// Flash memory interface clock enable + FLASHEN OFFSET(8) NUMBITS(1) [], + /// DMA2 clock enable + DMA2EN OFFSET(1) NUMBITS(1) [], + /// DMA1 clock enable + DMA1EN OFFSET(0) NUMBITS(1) [] + ], + AHB2ENR [ + /// Random Number Generator clock enable + RNGEN OFFSET(18) NUMBITS(1) [], + /// AES accelerator clock enable + AESEN OFFSET(16) NUMBITS(1) [], + /// ADC clock enable + ADCEN OFFSET(13) NUMBITS(1) [], + /// OTG full speed clock enable + OTGFSEN OFFSET(12) NUMBITS(1) [], + /// IO port H clock enable + GPIOHEN OFFSET(7) NUMBITS(1) [], + /// IO port G clock enable + GPIOGEN OFFSET(6) NUMBITS(1) [], + /// IO port F clock enable + GPIOFEN OFFSET(5) NUMBITS(1) [], + /// IO port E clock enable + GPIOEEN OFFSET(4) NUMBITS(1) [], + /// IO port D clock enable + GPIODEN OFFSET(3) NUMBITS(1) [], + /// IO port C clock enable + GPIOCEN OFFSET(2) NUMBITS(1) [], + /// IO port B clock enable + GPIOBEN OFFSET(1) NUMBITS(1) [], + /// IO port A clock enable + GPIOAEN OFFSET(0) NUMBITS(1) [] + ], + AHB3ENR [ + /// QSPIEN + QSPIEN OFFSET(8) NUMBITS(1) [], + /// Flexible memory controller clock enable + FMCEN OFFSET(0) NUMBITS(1) [] + ], + APB1ENR1 [ + /// Low power timer 1 clock enable + LPTIM1EN OFFSET(31) NUMBITS(1) [], + /// OPAMP interface clock enable + OPAMPEN OFFSET(30) NUMBITS(1) [], + /// DAC1 interface clock enable + DAC1EN OFFSET(29) NUMBITS(1) [], + /// Power interface clock enable + PWREN OFFSET(28) NUMBITS(1) [], + /// CAN1 clock enable + CAN1EN OFFSET(25) NUMBITS(1) [], + /// I2C3 clock enable + I2C3EN OFFSET(23) NUMBITS(1) [], + /// I2C2 clock enable + I2C2EN OFFSET(22) NUMBITS(1) [], + /// I2C1 clock enable + I2C1EN OFFSET(21) NUMBITS(1) [], + /// UART5 clock enable + UART5EN OFFSET(20) NUMBITS(1) [], + /// UART4 clock enable + UART4EN OFFSET(19) NUMBITS(1) [], + /// USART3 clock enable + USART3EN OFFSET(18) NUMBITS(1) [], + /// USART2 clock enable + USART2EN OFFSET(17) NUMBITS(1) [], + /// SPI3 clock enable + SPI3EN OFFSET(15) NUMBITS(1) [], + /// SPI2 clock enable + SPI2EN OFFSET(14) NUMBITS(1) [], + /// Window watchdog clock enable + WWDGEN OFFSET(11) NUMBITS(1) [], + /// RTC APB clock enable + RTCAPBEN OFFSET(10) NUMBITS(1) [], + /// LCD clock enable + LCDEN OFFSET(9) NUMBITS(1) [], + /// TIM7 timer clock enable + TIM7EN OFFSET(5) NUMBITS(1) [], + /// TIM6 timer clock enable + TIM6EN OFFSET(4) NUMBITS(1) [], + /// TIM5 timer clock enable + TIM5EN OFFSET(3) NUMBITS(1) [], + /// TIM4 timer clock enable + TIM4EN OFFSET(2) NUMBITS(1) [], + /// TIM3 timer clock enable + TIM3EN OFFSET(1) NUMBITS(1) [], + /// TIM2 timer clock enable + TIM2EN OFFSET(0) NUMBITS(1) [] + ], + APB1ENR2 [ + /// LPTIM2EN + LPTIM2EN OFFSET(5) NUMBITS(1) [], + /// Single wire protocol clock enable + SWPMI1EN OFFSET(2) NUMBITS(1) [], + /// Low power UART 1 clock enable + LPUART1EN OFFSET(0) NUMBITS(1) [] + ], + APB2ENR [ + /// DFSDM timer clock enable + DFSDMEN OFFSET(24) NUMBITS(1) [], + /// SAI2 clock enable + SAI2EN OFFSET(22) NUMBITS(1) [], + /// SAI1 clock enable + SAI1EN OFFSET(21) NUMBITS(1) [], + /// TIM17 timer clock enable + TIM17EN OFFSET(18) NUMBITS(1) [], + /// TIM16 timer clock enable + TIM16EN OFFSET(17) NUMBITS(1) [], + /// TIM15 timer clock enable + TIM15EN OFFSET(16) NUMBITS(1) [], + /// USART1clock enable + USART1EN OFFSET(14) NUMBITS(1) [], + /// TIM8 timer clock enable + TIM8EN OFFSET(13) NUMBITS(1) [], + /// SPI1 clock enable + SPI1EN OFFSET(12) NUMBITS(1) [], + /// TIM1 timer clock enable + TIM1EN OFFSET(11) NUMBITS(1) [], + /// SDMMC clock enable + SDMMCEN OFFSET(10) NUMBITS(1) [], + /// Firewall clock enable + FWEN OFFSET(7) NUMBITS(1) [], + /// SYSCFG clock enable + SYSCFGEN OFFSET(0) NUMBITS(1) [] + ], + AHB1SMENR [ + /// Touch Sensing Controller clocks enable during Sleep and Stop modes + TSCSMEN OFFSET(16) NUMBITS(1) [], + /// CRCSMEN + CRCSMEN OFFSET(12) NUMBITS(1) [], + /// SRAM1 interface clocks enable during Sleep and Stop modes + SRAM1SMEN OFFSET(9) NUMBITS(1) [], + /// Flash memory interface clocks enable during Sleep and Stop modes + FLASHSMEN OFFSET(8) NUMBITS(1) [], + /// DMA2 clocks enable during Sleep and Stop modes + DMA2SMEN OFFSET(1) NUMBITS(1) [], + /// DMA1 clocks enable during Sleep and Stop modes + DMA1SMEN OFFSET(0) NUMBITS(1) [] + ], + AHB2SMENR [ + /// Random Number Generator clocks enable during Sleep and Stop modes + RNGSMEN OFFSET(18) NUMBITS(1) [], + /// AES accelerator clocks enable during Sleep and Stop modes + AESSMEN OFFSET(16) NUMBITS(1) [], + /// ADC clocks enable during Sleep and Stop modes + ADCSMEN OFFSET(13) NUMBITS(1) [], + /// OTG full speed clocks enable during Sleep and Stop modes + OTGFSSMEN OFFSET(12) NUMBITS(1) [], + /// SRAM2 interface clocks enable during Sleep and Stop modes + SRAM2SMEN OFFSET(9) NUMBITS(1) [], + /// IO port H clocks enable during Sleep and Stop modes + GPIOHSMEN OFFSET(7) NUMBITS(1) [], + /// IO port G clocks enable during Sleep and Stop modes + GPIOGSMEN OFFSET(6) NUMBITS(1) [], + /// IO port F clocks enable during Sleep and Stop modes + GPIOFSMEN OFFSET(5) NUMBITS(1) [], + /// IO port E clocks enable during Sleep and Stop modes + GPIOESMEN OFFSET(4) NUMBITS(1) [], + /// IO port D clocks enable during Sleep and Stop modes + GPIODSMEN OFFSET(3) NUMBITS(1) [], + /// IO port C clocks enable during Sleep and Stop modes + GPIOCSMEN OFFSET(2) NUMBITS(1) [], + /// IO port B clocks enable during Sleep and Stop modes + GPIOBSMEN OFFSET(1) NUMBITS(1) [], + /// IO port A clocks enable during Sleep and Stop modes + GPIOASMEN OFFSET(0) NUMBITS(1) [] + ], + AHB3SMENR [ + /// QSPISMEN + QSPISMEN OFFSET(8) NUMBITS(1) [], + /// Flexible memory controller clocks enable during Sleep and Stop modes + FMCSMEN OFFSET(0) NUMBITS(1) [] + ], + APB1SMENR1 [ + /// Low power timer 1 clocks enable during Sleep and Stop modes + LPTIM1SMEN OFFSET(31) NUMBITS(1) [], + /// OPAMP interface clocks enable during Sleep and Stop modes + OPAMPSMEN OFFSET(30) NUMBITS(1) [], + /// DAC1 interface clocks enable during Sleep and Stop modes + DAC1SMEN OFFSET(29) NUMBITS(1) [], + /// Power interface clocks enable during Sleep and Stop modes + PWRSMEN OFFSET(28) NUMBITS(1) [], + /// CAN1 clocks enable during Sleep and Stop modes + CAN1SMEN OFFSET(25) NUMBITS(1) [], + /// I2C3 clocks enable during Sleep and Stop modes + I2C3SMEN OFFSET(23) NUMBITS(1) [], + /// I2C2 clocks enable during Sleep and Stop modes + I2C2SMEN OFFSET(22) NUMBITS(1) [], + /// I2C1 clocks enable during Sleep and Stop modes + I2C1SMEN OFFSET(21) NUMBITS(1) [], + /// UART5 clocks enable during Sleep and Stop modes + UART5SMEN OFFSET(20) NUMBITS(1) [], + /// UART4 clocks enable during Sleep and Stop modes + UART4SMEN OFFSET(19) NUMBITS(1) [], + /// USART3 clocks enable during Sleep and Stop modes + USART3SMEN OFFSET(18) NUMBITS(1) [], + /// USART2 clocks enable during Sleep and Stop modes + USART2SMEN OFFSET(17) NUMBITS(1) [], + /// SPI3 clocks enable during Sleep and Stop modes + SPI3SMEN OFFSET(15) NUMBITS(1) [], + /// SPI2 clocks enable during Sleep and Stop modes + SPI2SMEN OFFSET(14) NUMBITS(1) [], + /// Window watchdog clocks enable during Sleep and Stop modes + WWDGSMEN OFFSET(11) NUMBITS(1) [], + /// RTC APB clock enable during Sleep and Stop modes + RTCAPBSMEN OFFSET(10) NUMBITS(1) [], + /// LCD clocks enable during Sleep and Stop modes + LCDSMEN OFFSET(9) NUMBITS(1) [], + /// TIM7 timer clocks enable during Sleep and Stop modes + TIM7SMEN OFFSET(5) NUMBITS(1) [], + /// TIM6 timer clocks enable during Sleep and Stop modes + TIM6SMEN OFFSET(4) NUMBITS(1) [], + /// TIM5 timer clocks enable during Sleep and Stop modes + TIM5SMEN OFFSET(3) NUMBITS(1) [], + /// TIM4 timer clocks enable during Sleep and Stop modes + TIM4SMEN OFFSET(2) NUMBITS(1) [], + /// TIM3 timer clocks enable during Sleep and Stop modes + TIM3SMEN OFFSET(1) NUMBITS(1) [], + /// TIM2 timer clocks enable during Sleep and Stop modes + TIM2SMEN OFFSET(0) NUMBITS(1) [] + ], + APB1SMENR2 [ + /// LPTIM2SMEN + LPTIM2SMEN OFFSET(5) NUMBITS(1) [], + /// Single wire protocol clocks enable during Sleep and Stop modes + SWPMI1SMEN OFFSET(2) NUMBITS(1) [], + /// Low power UART 1 clocks enable during Sleep and Stop modes + LPUART1SMEN OFFSET(0) NUMBITS(1) [] + ], + APB2SMENR [ + /// DFSDM timer clocks enable during Sleep and Stop modes + DFSDMSMEN OFFSET(24) NUMBITS(1) [], + /// SAI2 clocks enable during Sleep and Stop modes + SAI2SMEN OFFSET(22) NUMBITS(1) [], + /// SAI1 clocks enable during Sleep and Stop modes + SAI1SMEN OFFSET(21) NUMBITS(1) [], + /// TIM17 timer clocks enable during Sleep and Stop modes + TIM17SMEN OFFSET(18) NUMBITS(1) [], + /// TIM16 timer clocks enable during Sleep and Stop modes + TIM16SMEN OFFSET(17) NUMBITS(1) [], + /// TIM15 timer clocks enable during Sleep and Stop modes + TIM15SMEN OFFSET(16) NUMBITS(1) [], + /// USART1clocks enable during Sleep and Stop modes + USART1SMEN OFFSET(14) NUMBITS(1) [], + /// TIM8 timer clocks enable during Sleep and Stop modes + TIM8SMEN OFFSET(13) NUMBITS(1) [], + /// SPI1 clocks enable during Sleep and Stop modes + SPI1SMEN OFFSET(12) NUMBITS(1) [], + /// TIM1 timer clocks enable during Sleep and Stop modes + TIM1SMEN OFFSET(11) NUMBITS(1) [], + /// SDMMC clocks enable during Sleep and Stop modes + SDMMCSMEN OFFSET(10) NUMBITS(1) [], + /// SYSCFG clocks enable during Sleep and Stop modes + SYSCFGSMEN OFFSET(0) NUMBITS(1) [] + ], + CCIPR [ + /// DFSDM clock source selection + DFSDMSEL OFFSET(31) NUMBITS(1) [ + PCLK = 0, + SYSCLK = 1 + ], + /// SWPMI1 clock source selection + SWPMI1SEL OFFSET(30) NUMBITS(1) [ + PCLK = 0, + HSI16 = 1 + ], + /// ADCs clock source selection + ADCSEL OFFSET(28) NUMBITS(2) [ + NoClock = 0, + PLLSAI1 = 1, + PLLSAI2 = 2, + SYSCLK = 3 + ], + /// 48 MHz clock source selection + CLK48SEL OFFSET(26) NUMBITS(2) [ + NoClock = 0, + PLLSAI1 = 1, + PLL = 2, + MSI = 3 + ], + /// SAI2 clock source selection + SAI2SEL OFFSET(24) NUMBITS(2) [ + PLLSAI1 = 0, + PLLSAI2 = 1, + PLL = 2, + EXTCLK = 3 + ], + /// SAI1 clock source selection + SAI1SEL OFFSET(22) NUMBITS(2) [ + PLLSAI1 = 0, + PLLSAI2 = 1, + PLL = 2, + EXTCLK = 3 + ], + /// Low power timer 2 clock source selection + LPTIM2SEL OFFSET(20) NUMBITS(2) [ + PCLK = 0, + LSI = 1, + HSI16 = 2, + LSE = 3 + ], + /// Low power timer 1 clock source selection + LPTIM1SEL OFFSET(18) NUMBITS(2) [ + PCLK = 0, + LSI = 1, + HSI16 = 2, + LSE = 3 + ], + /// I2C3 clock source selection + I2C3SEL OFFSET(16) NUMBITS(2) [ + PCLK = 0, + SYSCLK = 1, + HSI16 = 2 + ], + /// I2C2 clock source selection + I2C2SEL OFFSET(14) NUMBITS(2) [ + PCLK = 0, + SYSCLK = 1, + HSI16 = 2 + ], + /// I2C1 clock source selection + I2C1SEL OFFSET(12) NUMBITS(2) [ + PCLK = 0, + SYSCLK = 1, + HSI16 = 2 + ], + /// LPUART1 clock source selection + LPUART1SEL OFFSET(10) NUMBITS(2) [ + PCLK = 0, + SYSCLK = 1, + HSI16 = 2, + LSE = 3 + ], + /// UART5 clock source selection + UART5SEL OFFSET(8) NUMBITS(2) [ + PCLK = 0, + SYSCLK = 1, + HSI16 = 2, + LSE = 3 + ], + /// UART4 clock source selection + UART4SEL OFFSET(6) NUMBITS(2) [ + PCLK = 0, + SYSCLK = 1, + HSI16 = 2, + LSE = 3 + ], + /// USART3 clock source selection + USART3SEL OFFSET(4) NUMBITS(2) [ + PCLK = 0, + SYSCLK = 1, + HSI16 = 2, + LSE = 3 + ], + /// USART2 clock source selection + USART2SEL OFFSET(2) NUMBITS(2) [ + PCLK = 0, + SYSCLK = 1, + HSI16 = 2, + LSE = 3 + ], + /// USART1 clock source selection + USART1SEL OFFSET(0) NUMBITS(2) [ + PCLK = 0, + SYSCLK = 1, + HSI16 = 2, + LSE = 3 + ] + ], + BDCR [ + /// Low speed clock output selection + LSCOSEL OFFSET(25) NUMBITS(1) [ + LSI = 0, + LSE = 1 + ], + /// Low speed clock output enable + LSCOEN OFFSET(24) NUMBITS(1) [], + /// Backup domain software reset + BDRST OFFSET(16) NUMBITS(1) [], + /// RTC clock enable + RTCEN OFFSET(15) NUMBITS(1) [], + /// RTC clock source selection + RTCSEL OFFSET(8) NUMBITS(2) [ + NoClock = 0, + LSE = 1, + LSI = 2, + HSE = 3 + ], + /// CSS on LSE enable + LSECSSON OFFSET(5) NUMBITS(1) [], + /// CSS on LSE failure detection + LSECSSD OFFSET(6) NUMBITS(1) [], + /// SE oscillator drive capability + LSEDRV OFFSET(3) NUMBITS(2) [ + Low = 0, + MediumLow = 1, + MediumHigh = 2, + High = 3 + ], + /// LSE oscillator bypass + LSEBYP OFFSET(2) NUMBITS(1) [], + /// LSE oscillator ready + LSERDY OFFSET(1) NUMBITS(1) [], + /// LSE oscillator enable + LSEON OFFSET(0) NUMBITS(1) [] + ], + CSR [ + /// Low-power reset flag + LPWRRSTF OFFSET(31) NUMBITS(1) [], + /// Window watchdog reset flag + WWDGRSTF OFFSET(30) NUMBITS(1) [], + /// Independent window watchdog reset flag + IWDGRSTF OFFSET(29) NUMBITS(1) [], + /// Software reset flag + SFTRSTF OFFSET(28) NUMBITS(1) [], + /// BOR flag + BORRSTF OFFSET(27) NUMBITS(1) [], + /// Pin reset flag + PINRSTF OFFSET(26) NUMBITS(1) [], + /// Option byte loader reset flag + OBLRSTF OFFSET(25) NUMBITS(1) [], + /// Firewall reset flag + FIREWALLRSTF OFFSET(24) NUMBITS(1) [], + /// Remove reset flag + RMVF OFFSET(23) NUMBITS(1) [], + /// SI1 oscillator ready + LSIRDY OFFSET(1) NUMBITS(1) [], + /// LSI oscillator enable + LSION OFFSET(0) NUMBITS(1) [] + ] +]; + +const RCC_BASE: StaticRef = + unsafe { StaticRef::new(0x40021000 as *const RccRegisters) }; + +pub(crate) const DEFAULT_PLLM_VALUE: PLLM = PLLM::DivideBy1; +pub(crate) const DEFAULT_PLLN_VALUE: usize = 0x28; // 40 +pub(crate) const DEFAULT_PLLR_VALUE: PLLR = PLLR::DivideBy2; + +pub struct Rcc { + registers: StaticRef, +} + +impl Rcc { + pub fn new() -> Self { + let rcc = Self { + registers: RCC_BASE, + }; + rcc.init(); + rcc + } + + // Some clocks need to be initialized before use + fn init(&self) { + self.init_pll_clock(); + } + + // Init the PLL clock. + fn init_pll_clock(&self) { + self.set_pll_clock_source(PllSource::MSI); + self.set_pll_clock_m_divider(DEFAULT_PLLM_VALUE); + self.set_pll_clock_n_multiplier(DEFAULT_PLLN_VALUE); + self.set_pll_clock_r_divider(DEFAULT_PLLR_VALUE); + } + + // Get the current system clock source + pub(crate) fn get_sys_clock_source(&self) -> SysClockSource { + match self.registers.cfgr.read(CFGR::SWS) { + 0b00 => SysClockSource::MSI, + 0b01 => SysClockSource::HSI, + 0b11 => SysClockSource::PLL, + _ => todo!(), + } + } + + // Set the system clock source + // The source must be enabled + // NOTE: The flash latency also needs to be configured when changing the system clock frequency + pub(crate) fn set_sys_clock_source(&self, source: SysClockSource) { + self.registers.cfgr.modify(CFGR::SW.val(source as u32)); + } + + pub(crate) fn is_msi_clock_system_clock(&self) -> bool { + let system_clock_source = self.get_sys_clock_source(); + system_clock_source == SysClockSource::MSI + || system_clock_source == SysClockSource::PLL + && self.registers.pllcfgr.read(PLLCFGR::PLLSRC) == PllSource::MSI as u32 + } + + pub(crate) fn is_hsi_clock_system_clock(&self) -> bool { + let system_clock_source = self.get_sys_clock_source(); + system_clock_source == SysClockSource::HSI + || system_clock_source == SysClockSource::PLL + && self.registers.pllcfgr.read(PLLCFGR::PLLSRC) == PllSource::HSI as u32 + } + + /* HSI clock */ + // The HSI clock must not be configured as the system clock, either directly or indirectly. + pub(crate) fn disable_hsi_clock(&self) { + self.registers.cr.modify(CR::HSION::CLEAR); + } + + pub(crate) fn enable_hsi_clock(&self) { + self.registers.cr.modify(CR::HSION::SET); + } + + pub(crate) fn is_enabled_hsi_clock(&self) -> bool { + self.registers.cr.is_set(CR::HSION) + } + + // Indicates whether the HSI oscillator is stable + pub(crate) fn is_ready_hsi_clock(&self) -> bool { + self.registers.cr.is_set(CR::HSIRDY) + } + + /* Main PLL clock*/ + + // The main PLL clock must not be configured as the system clock + // when you want disable pll clock. + //First you need set sysclk source for other like MSI + pub(crate) fn disable_pll_clock(&self) { + self.registers.cr.modify(CR::PLLON::CLEAR); + } + + pub(crate) fn enable_pll_clock(&self) { + self.registers.cr.modify(CR::PLLON::SET); + } + + pub(crate) fn is_enabled_pll_clock(&self) -> bool { + self.registers.cr.is_set(CR::PLLON) + } + + // The PLL clock is locked when its signal is stable + pub(crate) fn is_locked_pll_clock(&self) -> bool { + self.registers.cr.is_set(CR::PLLRDY) + } + + pub(crate) fn get_pll_clock_source(&self) -> PllSource { + match self.registers.pllcfgr.read(PLLCFGR::PLLSRC) { + 0b00 => PllSource::NoClock, + 0b01 => PllSource::MSI, + 0b10 => PllSource::HSI, + _ => todo!("Unexpected PllSource!"), + } + } + + // This method must be called only when all PLL clocks are disabled + pub(crate) fn set_pll_clock_source(&self, source: PllSource) { + self.registers + .pllcfgr + .modify(PLLCFGR::PLLSRC.val(source as u32)); + } + + // This method must be called only when all PLL clocks are disabled + pub(crate) fn set_pll_clock_m_divider(&self, m: PLLM) { + self.registers.pllcfgr.modify(PLLCFGR::PLLM.val(m as u32)); + } + + // This method must be called only if the main PLL clock is disabled + pub(crate) fn set_pll_clock_n_multiplier(&self, n: usize) { + self.registers.pllcfgr.modify(PLLCFGR::PLLN.val(n as u32)); + } + + // This method must be called only if the main PLL clock is disabled + pub(crate) fn set_pll_clock_r_divider(&self, n: PLLR) { + self.registers.pllcfgr.modify(PLLCFGR::PLLR.val(n as u32)); + } + + /* MSI clock */ + + pub(crate) fn enable_msi_clock(&self) { + self.registers.cr.modify(CR::MSION::SET); + } + + pub(crate) fn disable_msi_clock(&self) { + self.registers.cr.modify(CR::MSION::CLEAR); + } + + pub(crate) fn is_enabled_msi_clock(&self) -> bool { + self.registers.cr.is_set(CR::MSION) + } + + // Indicates whether the MSI oscillator is stable + pub(crate) fn is_ready_msi_clock(&self) -> bool { + self.registers.cr.is_set(CR::MSIRDY) + } + + /* AHB prescaler */ + + pub(crate) fn set_ahb_prescaler(&self, ahb_prescaler: AHBPrescaler) { + self.registers + .cfgr + .modify(CFGR::HPRE.val(ahb_prescaler as u32)); + } + + pub(crate) fn get_ahb_prescaler(&self) -> AHBPrescaler { + match self.registers.cfgr.read(CFGR::HPRE) { + 0b1000 => AHBPrescaler::DivideBy2, + 0b1001 => AHBPrescaler::DivideBy4, + 0b1010 => AHBPrescaler::DivideBy8, + 0b1011 => AHBPrescaler::DivideBy16, + 0b1100 => AHBPrescaler::DivideBy64, + 0b1101 => AHBPrescaler::DivideBy128, + 0b1110 => AHBPrescaler::DivideBy256, + 0b1111 => AHBPrescaler::DivideBy512, + _ => AHBPrescaler::DivideBy1, + } + } + + /* APB1 prescaler */ + + pub(crate) fn set_apb1_prescaler(&self, apb1_prescaler: APBPrescaler) { + self.registers + .cfgr + .modify(CFGR::PPRE1.val(apb1_prescaler as u32)); + } + + pub(crate) fn get_apb1_prescaler(&self) -> APBPrescaler { + match self.registers.cfgr.read(CFGR::PPRE1) { + 0b100 => APBPrescaler::DivideBy2, + 0b101 => APBPrescaler::DivideBy4, + 0b110 => APBPrescaler::DivideBy8, + 0b111 => APBPrescaler::DivideBy16, + _ => APBPrescaler::DivideBy1, // 0b0xx means no division + } + } + + /* APB2 prescaler */ + + pub(crate) fn set_apb2_prescaler(&self, apb2_prescaler: APBPrescaler) { + self.registers + .cfgr + .modify(CFGR::PPRE2.val(apb2_prescaler as u32)); + } + + pub(crate) fn get_apb2_prescaler(&self) -> APBPrescaler { + match self.registers.cfgr.read(CFGR::PPRE2) { + 0b100 => APBPrescaler::DivideBy2, + 0b101 => APBPrescaler::DivideBy4, + 0b110 => APBPrescaler::DivideBy8, + 0b111 => APBPrescaler::DivideBy16, + _ => APBPrescaler::DivideBy1, // 0b0xx means no division + } + } + + // SYSCFG clock + + pub(crate) fn is_enabled_syscfg_clock(&self) -> bool { + self.registers.apb2enr.is_set(APB2ENR::SYSCFGEN) + } + + pub(crate) fn enable_syscfg_clock(&self) { + self.registers.apb2enr.modify(APB2ENR::SYSCFGEN::SET) + } + + pub(crate) fn disable_syscfg_clock(&self) { + self.registers.apb2enr.modify(APB2ENR::SYSCFGEN::CLEAR) + } + + // DMA1 clock + + pub(crate) fn is_enabled_dma1_clock(&self) -> bool { + self.registers.ahb1enr.is_set(AHB1ENR::DMA1EN) + } + + pub(crate) fn enable_dma1_clock(&self) { + self.registers.ahb1enr.modify(AHB1ENR::DMA1EN::SET) + } + + pub(crate) fn disable_dma1_clock(&self) { + self.registers.ahb1enr.modify(AHB1ENR::DMA1EN::CLEAR) + } + + // DMA2 clock + + pub(crate) fn is_enabled_dma2_clock(&self) -> bool { + self.registers.ahb1enr.is_set(AHB1ENR::DMA2EN) + } + + pub(crate) fn enable_dma2_clock(&self) { + self.registers.ahb1enr.modify(AHB1ENR::DMA2EN::SET) + } + + pub(crate) fn disable_dma2_clock(&self) { + self.registers.ahb1enr.modify(AHB1ENR::DMA2EN::CLEAR) + } + + // GPIOH clock + + pub(crate) fn is_enabled_gpioh_clock(&self) -> bool { + self.registers.ahb2enr.is_set(AHB2ENR::GPIOHEN) + } + + pub(crate) fn enable_gpioh_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIOHEN::SET) + } + + pub(crate) fn disable_gpioh_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIOHEN::CLEAR) + } + + // GPIOG clock + + pub(crate) fn is_enabled_gpiog_clock(&self) -> bool { + self.registers.ahb2enr.is_set(AHB2ENR::GPIOGEN) + } + + pub(crate) fn enable_gpiog_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIOGEN::SET) + } + + pub(crate) fn disable_gpiog_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIOGEN::CLEAR) + } + + // GPIOF clock + + pub(crate) fn is_enabled_gpiof_clock(&self) -> bool { + self.registers.ahb2enr.is_set(AHB2ENR::GPIOFEN) + } + + pub(crate) fn enable_gpiof_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIOFEN::SET) + } + + pub(crate) fn disable_gpiof_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIOFEN::CLEAR) + } + + // GPIOE clock + + pub(crate) fn is_enabled_gpioe_clock(&self) -> bool { + self.registers.ahb2enr.is_set(AHB2ENR::GPIOEEN) + } + + pub(crate) fn enable_gpioe_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIOEEN::SET) + } + + pub(crate) fn disable_gpioe_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIOEEN::CLEAR) + } + + // GPIOD clock + + pub(crate) fn is_enabled_gpiod_clock(&self) -> bool { + self.registers.ahb2enr.is_set(AHB2ENR::GPIODEN) + } + + pub(crate) fn enable_gpiod_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIODEN::SET) + } + + pub(crate) fn disable_gpiod_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIODEN::CLEAR) + } + + // GPIOC clock + + pub(crate) fn is_enabled_gpioc_clock(&self) -> bool { + self.registers.ahb2enr.is_set(AHB2ENR::GPIOCEN) + } + + pub(crate) fn enable_gpioc_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIOCEN::SET) + } + + pub(crate) fn disable_gpioc_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIOCEN::CLEAR) + } + + // GPIOB clock + + pub(crate) fn is_enabled_gpiob_clock(&self) -> bool { + self.registers.ahb2enr.is_set(AHB2ENR::GPIOBEN) + } + + pub(crate) fn enable_gpiob_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIOBEN::SET) + } + + pub(crate) fn disable_gpiob_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIOBEN::CLEAR) + } + + // GPIOA clock + + pub(crate) fn is_enabled_gpioa_clock(&self) -> bool { + self.registers.ahb2enr.is_set(AHB2ENR::GPIOAEN) + } + + pub(crate) fn enable_gpioa_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIOAEN::SET) + } + + pub(crate) fn disable_gpioa_clock(&self) { + self.registers.ahb2enr.modify(AHB2ENR::GPIOAEN::CLEAR) + } + + // USART1 clock + + pub(crate) fn is_enabled_usart1_clock(&self) -> bool { + self.registers.apb2enr.is_set(APB2ENR::USART1EN) + } + + pub(crate) fn enable_usart1_clock(&self) { + self.registers.apb2enr.modify(APB2ENR::USART1EN::SET) + } + + pub(crate) fn disable_usart1_clock(&self) { + self.registers.apb2enr.modify(APB2ENR::USART1EN::CLEAR) + } + + // USART2 clock + + pub(crate) fn is_enabled_usart2_clock(&self) -> bool { + self.registers.apb1enr1.is_set(APB1ENR1::USART2EN) + } + + pub(crate) fn enable_usart2_clock(&self) { + self.registers.apb1enr1.modify(APB1ENR1::USART2EN::SET) + } + + pub(crate) fn disable_usart2_clock(&self) { + self.registers.apb1enr1.modify(APB1ENR1::USART2EN::CLEAR) + } + + // USART3 clock + + pub(crate) fn is_enabled_usart3_clock(&self) -> bool { + self.registers.apb1enr1.is_set(APB1ENR1::USART3EN) + } + + pub(crate) fn enable_usart3_clock(&self) { + self.registers.apb1enr1.modify(APB1ENR1::USART3EN::SET) + } + + pub(crate) fn disable_usart3_clock(&self) { + self.registers.apb1enr1.modify(APB1ENR1::USART3EN::CLEAR) + } +} + +pub(crate) enum PLLM { + DivideBy1 = 0, + DivideBy2 = 1, + DivideBy3 = 2, + DivideBy4 = 3, + DivideBy5 = 4, + DivideBy6 = 5, + DivideBy7 = 6, + DivideBy8 = 7, +} + +impl From for PLLM { + fn from(item: usize) -> PLLM { + match item { + 1 => PLLM::DivideBy1, + 2 => PLLM::DivideBy2, + 3 => PLLM::DivideBy3, + 4 => PLLM::DivideBy4, + 5 => PLLM::DivideBy5, + 6 => PLLM::DivideBy6, + 7 => PLLM::DivideBy7, + 8 => PLLM::DivideBy8, + _ => todo!(), + } + } +} + +impl From for usize { + fn from(item: PLLM) -> usize { + match item { + PLLM::DivideBy1 => 1, + PLLM::DivideBy2 => 2, + PLLM::DivideBy3 => 3, + PLLM::DivideBy4 => 4, + PLLM::DivideBy5 => 5, + PLLM::DivideBy6 => 6, + PLLM::DivideBy7 => 7, + PLLM::DivideBy8 => 8, + } + } +} + +pub(crate) enum PLLR { + DivideBy2 = 0, + DivideBy4 = 1, + DivideBy6 = 2, + DivideBy8 = 3, +} + +impl From for PLLR { + fn from(item: usize) -> PLLR { + match item { + 2 => PLLR::DivideBy2, + 4 => PLLR::DivideBy4, + 6 => PLLR::DivideBy6, + 8 => PLLR::DivideBy8, + _ => todo!(), + } + } +} + +impl From for usize { + fn from(item: PLLR) -> usize { + match item { + PLLR::DivideBy2 => 2, + PLLR::DivideBy4 => 4, + PLLR::DivideBy6 => 6, + PLLR::DivideBy8 => 8, + } + } +} + +/// Clock sources for the CPU +#[derive(Clone, Copy, PartialEq, Debug)] +pub enum SysClockSource { + MSI = 0b00, + HSI = 0b01, + //HSE = 0b10, Uncomment this when support for HSE is added + PLL = 0b11, +} + +#[derive(Clone, Copy, PartialEq, Debug)] +pub enum PllSource { + NoClock = 0b00, + MSI = 0b01, + HSI = 0b10, + // HSE = 0b11, Uncomment this when support for HSE is added +} + +#[derive(Clone, Copy, PartialEq, Debug)] +pub enum APBPrescaler { + DivideBy1 = 0b000, // No division + DivideBy2 = 0b100, + DivideBy4 = 0b101, + DivideBy8 = 0b110, + DivideBy16 = 0b111, +} + +impl From for usize { + fn from(item: APBPrescaler) -> Self { + match item { + APBPrescaler::DivideBy1 => 1, + APBPrescaler::DivideBy2 => 2, + APBPrescaler::DivideBy4 => 4, + APBPrescaler::DivideBy8 => 8, + APBPrescaler::DivideBy16 => 16, + } + } +} + +#[derive(Clone, Copy, PartialEq, Debug)] +pub enum AHBPrescaler { + DivideBy1 = 0b0000, + DivideBy2 = 0b1000, + DivideBy4 = 0b1001, + DivideBy8 = 0b1010, + DivideBy16 = 0b1011, + DivideBy64 = 0b1100, + DivideBy128 = 0b1101, + DivideBy256 = 0b1110, + DivideBy512 = 0b1111, +} + +impl From for usize { + fn from(item: AHBPrescaler) -> usize { + match item { + AHBPrescaler::DivideBy1 => 1, + AHBPrescaler::DivideBy2 => 2, + AHBPrescaler::DivideBy4 => 4, + AHBPrescaler::DivideBy8 => 8, + AHBPrescaler::DivideBy16 => 16, + AHBPrescaler::DivideBy64 => 64, + AHBPrescaler::DivideBy128 => 128, + AHBPrescaler::DivideBy256 => 256, + AHBPrescaler::DivideBy512 => 512, + } + } +} diff --git a/chips/stm32l4xx/src/syscfg.rs b/chips/stm32l4xx/src/syscfg.rs new file mode 100644 index 0000000000..0741ddc6e8 --- /dev/null +++ b/chips/stm32l4xx/src/syscfg.rs @@ -0,0 +1,266 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +use enum_primitive::cast::FromPrimitive; +use enum_primitive::enum_from_primitive; +use kernel::platform::chip::ClockInterface; +use kernel::utilities::registers::interfaces::ReadWriteable; +use kernel::utilities::registers::{register_bitfields, ReadWrite}; +use kernel::utilities::StaticRef; + +use crate::clocks::{phclk, Stm32l4Clocks}; +use crate::gpio; + +/// System configuration controller (STM32L476) +/// Reference: RM0351 (SYSCFG chapter) +#[repr(C)] +struct SyscfgRegisters { + /// memory remap register + memrmp: ReadWrite, + /// configuration register + cfgr: ReadWrite, + /// external interrupt configuration register 1 + exticr1: ReadWrite, + /// external interrupt configuration register 2 + exticr2: ReadWrite, + /// external interrupt configuration register 3 + exticr3: ReadWrite, + /// external interrupt configuration register 4 + exticr4: ReadWrite, + /// SRAM2 control and status register + scsr: ReadWrite, + /// configuration register 2 + cfgr2: ReadWrite, + /// SRAM2 write protection register + swpr: ReadWrite, + /// SRAM2 key register + skr: ReadWrite, +} + +register_bitfields![u32, + MEMRMP [ + /// Memory mapping selection + MEM_MODE OFFSET(0) NUMBITS(3) [] + ], + CFGR [ + /// FPU interrupt enable bits (aggregate placeholder) + FPU_IE OFFSET(26) NUMBITS(6) [], + /// Booster enable (improves performance at low VOS) (optional) + BOOSTEN OFFSET(8) NUMBITS(1) [] + ], + EXTICR1 [ + EXTI3 OFFSET(12) NUMBITS(4) [], + EXTI2 OFFSET(8) NUMBITS(4) [], + EXTI1 OFFSET(4) NUMBITS(4) [], + EXTI0 OFFSET(0) NUMBITS(4) [] + ], + EXTICR2 [ + EXTI7 OFFSET(12) NUMBITS(4) [], + EXTI6 OFFSET(8) NUMBITS(4) [], + EXTI5 OFFSET(4) NUMBITS(4) [], + EXTI4 OFFSET(0) NUMBITS(4) [] + ], + EXTICR3 [ + EXTI11 OFFSET(12) NUMBITS(4) [], + EXTI10 OFFSET(8) NUMBITS(4) [], + EXTI9 OFFSET(4) NUMBITS(4) [], + EXTI8 OFFSET(0) NUMBITS(4) [] + ], + EXTICR4 [ + EXTI15 OFFSET(12) NUMBITS(4) [], + EXTI14 OFFSET(8) NUMBITS(4) [], + EXTI13 OFFSET(4) NUMBITS(4) [], + EXTI12 OFFSET(0) NUMBITS(4) [] + ], + SCSR [ + /// SRAM2 erase + SRAM2ER OFFSET(0) NUMBITS(1) [], + /// SRAM2 busy (erase ongoing) + SRAM2BSY OFFSET(1) NUMBITS(1) [] + ], + CFGR2 [ + /// Cortex-M4 LOCKUP output enable + LOCUP_LOCK OFFSET(0) NUMBITS(1) [], + /// SRAM parity error address latch disable + BYP_ADDR_PAR OFFSET(1) NUMBITS(1) [] + ], + SWPR [ + /// SRAM2 pages write protection bits (0..23 for 24 pages on L4 family with 192KB SRAM2) + P0 OFFSET(0) NUMBITS(1) [], + P1 OFFSET(1) NUMBITS(1) [], + P2 OFFSET(2) NUMBITS(1) [], + P3 OFFSET(3) NUMBITS(1) [], + P4 OFFSET(4) NUMBITS(1) [], + P5 OFFSET(5) NUMBITS(1) [], + P6 OFFSET(6) NUMBITS(1) [], + P7 OFFSET(7) NUMBITS(1) [], + P8 OFFSET(8) NUMBITS(1) [], + P9 OFFSET(9) NUMBITS(1) [], + P10 OFFSET(10) NUMBITS(1) [], + P11 OFFSET(11) NUMBITS(1) [], + P12 OFFSET(12) NUMBITS(1) [], + P13 OFFSET(13) NUMBITS(1) [], + P14 OFFSET(14) NUMBITS(1) [], + P15 OFFSET(15) NUMBITS(1) [], + P16 OFFSET(16) NUMBITS(1) [], + P17 OFFSET(17) NUMBITS(1) [], + P18 OFFSET(18) NUMBITS(1) [], + P19 OFFSET(19) NUMBITS(1) [], + P20 OFFSET(20) NUMBITS(1) [], + P21 OFFSET(21) NUMBITS(1) [], + P22 OFFSET(22) NUMBITS(1) [], + P23 OFFSET(23) NUMBITS(1) [] + ], + SKR [ + /// SRAM2 write protection unlock key + KEY OFFSET(0) NUMBITS(8) [] + ] +]; + +const SYSCFG_BASE: StaticRef = + unsafe { StaticRef::new(0x40010000 as *const SyscfgRegisters) }; + +enum_from_primitive! { + #[repr(u32)] + /// SYSCFG EXTI configuration [^1] + /// + /// [^1]: Section 9.2.3, page 317 of reference manual + enum ExtiCrId { + PA = 0b0000, + PB = 0b0001, + PC = 0b0010, + PD = 0b0011, + PE = 0b0100, + PF = 0b0101, + PG = 0b0110, + PH = 0b0111, + } +} + +pub struct Syscfg<'a> { + registers: StaticRef, + clock: SyscfgClock<'a>, +} + +impl<'a> Syscfg<'a> { + pub const fn new(clocks: &'a dyn Stm32l4Clocks) -> Self { + Self { + registers: SYSCFG_BASE, + clock: SyscfgClock(phclk::PeripheralClock::new( + phclk::PeripheralClockType::APB2(phclk::PCLK2::SYSCFG), + clocks, + )), + } + } + + pub fn is_enabled_clock(&self) -> bool { + self.clock.is_enabled() + } + + pub fn enable_clock(&self) { + self.clock.enable(); + } + + pub fn disable_clock(&self) { + self.clock.disable(); + } + + /// Configures the SYSCFG_EXTICR{1, 2, 3, 4} registers + pub fn configure_interrupt(&self, pinid: gpio::PinId) { + let exticrid = self.get_exticrid_from_port_num(pinid.get_port_number()); + + let pin_num = pinid.get_pin_number(); + match pin_num { + // SYSCFG_EXTICR1 + 0b0000 => self + .registers + .exticr1 + .modify(EXTICR1::EXTI0.val(exticrid as u32)), + 0b0001 => self + .registers + .exticr1 + .modify(EXTICR1::EXTI1.val(exticrid as u32)), + 0b0010 => self + .registers + .exticr1 + .modify(EXTICR1::EXTI2.val(exticrid as u32)), + 0b0011 => self + .registers + .exticr1 + .modify(EXTICR1::EXTI3.val(exticrid as u32)), + // SYSCFG_EXTICR2 + 0b0100 => self + .registers + .exticr2 + .modify(EXTICR2::EXTI4.val(exticrid as u32)), + 0b0101 => self + .registers + .exticr2 + .modify(EXTICR2::EXTI5.val(exticrid as u32)), + 0b0110 => self + .registers + .exticr2 + .modify(EXTICR2::EXTI6.val(exticrid as u32)), + 0b0111 => self + .registers + .exticr2 + .modify(EXTICR2::EXTI7.val(exticrid as u32)), + // SYSCFG_EXTICR3 + 0b1000 => self + .registers + .exticr3 + .modify(EXTICR3::EXTI8.val(exticrid as u32)), + 0b1001 => self + .registers + .exticr3 + .modify(EXTICR3::EXTI9.val(exticrid as u32)), + 0b1010 => self + .registers + .exticr3 + .modify(EXTICR3::EXTI10.val(exticrid as u32)), + 0b1011 => self + .registers + .exticr3 + .modify(EXTICR3::EXTI11.val(exticrid as u32)), + // SYSCFG_EXTICR4 + 0b1100 => self + .registers + .exticr4 + .modify(EXTICR4::EXTI12.val(exticrid as u32)), + 0b1101 => self + .registers + .exticr4 + .modify(EXTICR4::EXTI13.val(exticrid as u32)), + 0b1110 => self + .registers + .exticr4 + .modify(EXTICR4::EXTI14.val(exticrid as u32)), + 0b1111 => self + .registers + .exticr4 + .modify(EXTICR4::EXTI15.val(exticrid as u32)), + _ => {} + } + } + + fn get_exticrid_from_port_num(&self, port_num: u8) -> ExtiCrId { + ExtiCrId::from_u32(u32::from(port_num)).unwrap() + } +} + +struct SyscfgClock<'a>(phclk::PeripheralClock<'a>); + +impl ClockInterface for SyscfgClock<'_> { + fn is_enabled(&self) -> bool { + self.0.is_enabled() + } + + fn enable(&self) { + self.0.enable(); + } + + fn disable(&self) { + self.0.disable(); + } +} diff --git a/chips/stm32l4xx/src/usart.rs b/chips/stm32l4xx/src/usart.rs new file mode 100644 index 0000000000..f3c6d5b000 --- /dev/null +++ b/chips/stm32l4xx/src/usart.rs @@ -0,0 +1,784 @@ +// Licensed under the Apache License, Version 2.0 or the MIT License. +// SPDX-License-Identifier: Apache-2.0 OR MIT +// Author: Kamil Duljas + +use core::cell::Cell; +use kernel::deferred_call::{DeferredCall, DeferredCallClient}; +use kernel::hil; +use kernel::platform::chip::ClockInterface; +use kernel::utilities::cells::{OptionalCell, TakeCell}; +use kernel::utilities::registers::interfaces::{ReadWriteable, Readable, Writeable}; +use kernel::utilities::registers::{register_bitfields, ReadOnly, ReadWrite}; +use kernel::utilities::StaticRef; +use kernel::ErrorCode; + +use crate::clocks::{phclk, Stm32l4Clocks}; + +/// Universal synchronous asynchronous receiver transmitter +/// Register layout per RM0351: CR1, CR2, CR3, BRR, GTPR, RTOR, RQR, ISR, ICR, RDR, TDR, PRESC +#[repr(C)] +pub struct UsartRegisters { + /// Control register 1 + cr1: ReadWrite, // 0x00 + /// Control register 2 + cr2: ReadWrite, // 0x04 + /// Control register 3 + cr3: ReadWrite, // 0x08 + /// Baud rate register + brr: ReadWrite, // 0x0C + /// Guard time and prescaler register (smartcard/IrDA) + gtpr: ReadWrite, // 0x10 + /// Receiver timeout register + rtor: ReadWrite, // 0x14 + /// Request register + rqr: ReadWrite, // 0x18 + /// Interrupt & status register + isr: ReadOnly, // 0x1C + /// Interrupt flag clear register + icr: ReadWrite, // 0x20 (write 1 to clear) + /// Receive data register + rdr: ReadOnly, // 0x24 + /// Transmit data register + tdr: ReadWrite, // 0x28 + /// Prescaler register + presc: ReadWrite, // 0x2C +} + +register_bitfields![u32, + CR1 [ + /// FIFO mode enable + FIFOEN OFFSET(29) NUMBITS(1) [], + /// Word length bit 1 + M1 OFFSET(28) NUMBITS(1) [], + /// End of Block interrupt enable + EOBIE OFFSET(27) NUMBITS(1) [], + /// Receiver timeout interrupt enable + RTOIE OFFSET(26) NUMBITS(1) [], + /// Driver Enable assertion time + DEAT OFFSET(21) NUMBITS(5) [], + /// Driver Enable de-assertion time + DEDT OFFSET(16) NUMBITS(5) [], + /// Oversampling mode + OVER8 OFFSET(15) NUMBITS(1) [], + /// Character match interrupt enable + CMIE OFFSET(14) NUMBITS(1) [], + /// Mute mode enable + MME OFFSET(13) NUMBITS(1) [], + /// Word length bit 0 + M0 OFFSET(12) NUMBITS(1) [], + /// Wakeup method + WAKE OFFSET(11) NUMBITS(1) [], + /// Parity control enable + PCE OFFSET(10) NUMBITS(1) [], + /// Parity selection + PS OFFSET(9) NUMBITS(1) [], + /// PE interrupt enable + PEIE OFFSET(8) NUMBITS(1) [], + /// TXE interrupt enable + TXEIE OFFSET(7) NUMBITS(1) [], + /// Transmission complete interrupt enable + TCIE OFFSET(6) NUMBITS(1) [], + /// RXNE interrupt enable + RXNEIE OFFSET(5) NUMBITS(1) [], + /// IDLE interrupt enable + IDLEIE OFFSET(4) NUMBITS(1) [], + /// Transmitter enable + TE OFFSET(3) NUMBITS(1) [], + /// Receiver enable + RE OFFSET(2) NUMBITS(1) [], + /// USART enable in Stop mode + UESM OFFSET(1) NUMBITS(1) [], + /// USART enable + UE OFFSET(0) NUMBITS(1) [], + ], + CR2 [ + /// Address of the USART node (4 bits MSB) + ADD4_7 OFFSET(28) NUMBITS(4) [], + /// Address of the USART node (4 bits LSB) + ADD0_3 OFFSET(24) NUMBITS(4) [], + /// Receiver timeout enable + RTOEN OFFSET(23) NUMBITS(1) [], + /// Auto baud rate mode + ABRMOD OFFSET(21) NUMBITS(2) [], + /// Auto baud rate enable + ABREN OFFSET(20) NUMBITS(1) [], + /// Most significant bit first + MSBFIRST OFFSET(19) NUMBITS(1) [], + /// Binary data inversion + DATAINV OFFSET(18) NUMBITS(1) [], + /// TX pin active level inversion + TXINV OFFSET(17) NUMBITS(1) [], + /// RX pin active level inversion + RXINV OFFSET(16) NUMBITS(1) [], + /// Swap TX/RX pins + SWAP OFFSET(15) NUMBITS(1) [], + /// LIN mode enable + LINEN OFFSET(14) NUMBITS(1) [], + /// STOP bits + STOP OFFSET(12) NUMBITS(2) [], + /// Clock enable + CLKEN OFFSET(11) NUMBITS(1) [], + /// Clock polarity + CPOL OFFSET(10) NUMBITS(1) [], + /// Clock phase + CPHA OFFSET(9) NUMBITS(1) [], + /// Last bit clock pulse + LBCL OFFSET(8) NUMBITS(1) [], + /// LIN break detection interrupt enable + LBDIE OFFSET(6) NUMBITS(1) [], + /// lin break detection length + LBDL OFFSET(5) NUMBITS(1) [], + /// 7-bit Address Detection/4-bit Address Detection + ADDM7 OFFSET(4) NUMBITS(1) [] + ], + CR3 [ + /// Wakeup from Stop mode interrupt flag clear + WUFIE OFFSET(22) NUMBITS(1) [], + /// Wakeup from Stop mode interrupt flag selection + WUS OFFSET(20) NUMBITS(2) [], + /// Smartcard auto-retry count + SCARCNT OFFSET(17) NUMBITS(3) [], + /// Driver enable polarity selection + DEP OFFSET(15) NUMBITS(1) [], + /// Driver enable mode + DEM OFFSET(14) NUMBITS(1) [], + /// DMA Disable on Reception Error + DDRE OFFSET(13) NUMBITS(1) [], + /// Overrun Disable + OVRDIS OFFSET(12) NUMBITS(1) [], + /// One sample bit method enable + ONEBIT OFFSET(11) NUMBITS(1) [], + /// CTS interrupt enable + CTSIE OFFSET(10) NUMBITS(1) [], + /// CTS enable + CTSE OFFSET(9) NUMBITS(1) [], + /// RTS enable + RTSE OFFSET(8) NUMBITS(1) [], + /// DMA enable transmitter + DMAT OFFSET(7) NUMBITS(1) [], + /// DMA enable receiver + DMAR OFFSET(6) NUMBITS(1) [], + /// Smartcard mode enable + SCEN OFFSET(5) NUMBITS(1) [], + /// Smartcard NACK enable + NACK OFFSET(4) NUMBITS(1) [], + /// Half-duplex selection + HDSEL OFFSET(3) NUMBITS(1) [], + /// IrDA low-power + IRLP OFFSET(2) NUMBITS(1) [], + /// IrDA mode enable + IREN OFFSET(1) NUMBITS(1) [], + /// Error interrupt enable + EIE OFFSET(0) NUMBITS(1) [] + ], + BRR [ + /// Baud rate register (write full value) + BRR OFFSET(0) NUMBITS(16) [] + ], + GTPR [ + /// Guard time value + GT OFFSET(8) NUMBITS(8) [], + /// Prescaler value + PSC OFFSET(0) NUMBITS(8) [] + ], + RTOR [ + /// Block Length + BLEN OFFSET(24) NUMBITS(8) [], + /// Receiver timeout value + RTO OFFSET(0) NUMBITS(24) [] + ], + RQR [ + /// Transmit data flush request + TXFRQ OFFSET(4) NUMBITS(1) [], + /// Receive data flush request + RXFRQ OFFSET(3) NUMBITS(1) [], + /// Mute mode request + MMRQ OFFSET(2) NUMBITS(1) [], + /// Send break request + SBKRQ OFFSET(1) NUMBITS(1) [], + /// Auto baud rate request + ABRRQ OFFSET(0) NUMBITS(1) [] + ], + ISR [ + /// Parity error + PE OFFSET(0) NUMBITS(1) [], + /// Framing error + FE OFFSET(1) NUMBITS(1) [], + /// Noise error + NE OFFSET(2) NUMBITS(1) [], + /// Overrun error + ORE OFFSET(3) NUMBITS(1) [], + /// IDLE line detected + IDLE OFFSET(4) NUMBITS(1) [], + /// Read data register not empty + RXNE OFFSET(5) NUMBITS(1) [], + /// Transmission complete + TC OFFSET(6) NUMBITS(1) [], + /// Transmit data register empty + TXE OFFSET(7) NUMBITS(1) [], + /// LIN break detection flag + LBDF OFFSET(8) NUMBITS(1) [], + /// CTS interrupt flag + CTSIF OFFSET(9) NUMBITS(1) [], + /// CTS flag + CTS OFFSET(10) NUMBITS(1) [], + /// Receiver timeout + RTOF OFFSET(11) NUMBITS(1) [], + /// End of block flag + EOBF OFFSET(12) NUMBITS(1) [], + /// Auto baud rate error + ABRE OFFSET(14) NUMBITS(1) [], + /// Auto baud rate flag + ABRF OFFSET(15) NUMBITS(1) [], + /// Busy flag + BUSY OFFSET(16) NUMBITS(1) [], + /// Character match flag + CMF OFFSET(17) NUMBITS(1) [], + /// Send break flag + SBKF OFFSET(18) NUMBITS(1) [], + /// Receiver wakeup from Mute mode + RWU OFFSET(19) NUMBITS(1) [], + /// Wakeup from Stop mode flag + WUF OFFSET(20) NUMBITS(1) [], + /// Transmit enable acknowledge flag + TEACK OFFSET(21) NUMBITS(1) [], + /// Receive enable acknowledge flag + REACK OFFSET(22) NUMBITS(1) [] + ], + ICR [ + /// Parity error clear flag + PECF OFFSET(0) NUMBITS(1) [], + /// Framing error clear flag + FECF OFFSET(1) NUMBITS(1) [], + /// Noise error clear flag + NECF OFFSET(2) NUMBITS(1) [], + /// Overrun error clear flag + ORECF OFFSET(3) NUMBITS(1) [], + /// IDLE line detected clear flag + IDLECF OFFSET(4) NUMBITS(1) [], + /// Transmission complete clear flag + TCCF OFFSET(6) NUMBITS(1) [], + /// LIN break detection clear flag + LBDCF OFFSET(8) NUMBITS(1) [], + /// CTS clear flag + CTSCF OFFSET(9) NUMBITS(1) [], + /// Receiver timeout clear flag + RTOCF OFFSET(11) NUMBITS(1) [], + /// End of block clear flag + EOBCF OFFSET(12) NUMBITS(1) [], + /// Character match clear flag + CMCF OFFSET(17) NUMBITS(1) [], + /// Wakeup from Stop mode clear flag + WUCF OFFSET(20) NUMBITS(1) [] + ], + RDR [ + /// Receive data value + RDR OFFSET(0) NUMBITS(9) [] + ], + TDR [ + /// Transmit data value + TDR OFFSET(0) NUMBITS(9) [] + ], + PRESC [ + /// Prescaler value + PRESCALER OFFSET(0) NUMBITS(4) [] + ] +]; + +// STM32L476 register boundary addresses +pub const USART1_BASE: StaticRef = + unsafe { StaticRef::new(0x40013800 as *const UsartRegisters) }; +pub const USART2_BASE: StaticRef = + unsafe { StaticRef::new(0x40004400 as *const UsartRegisters) }; +pub const USART3_BASE: StaticRef = + unsafe { StaticRef::new(0x40004800 as *const UsartRegisters) }; + +macro_rules! usart_new { + ($base:expr, $clock_type:expr, $clocks:expr) => { + Usart { + registers: $base, + clock: UsartClock(phclk::PeripheralClock::new($clock_type, $clocks)), + tx_client: OptionalCell::empty(), + rx_client: OptionalCell::empty(), + tx_buffer: TakeCell::empty(), + tx_len: Cell::new(0), + tx_index: Cell::new(0), + rx_buffer: TakeCell::empty(), + rx_len: Cell::new(0), + rx_index: Cell::new(0), + usart_tx_state: Cell::new(USARTStateTX::Idle), + usart_rx_state: Cell::new(USARTStateRX::Idle), + deferred_call: DeferredCall::new(), + } + }; +} + +#[allow(non_camel_case_types)] +#[derive(Copy, Clone, PartialEq)] +enum USARTStateRX { + Idle, + Receiving, + Aborted(Result<(), ErrorCode>, hil::uart::Error), +} + +#[allow(non_camel_case_types)] +#[derive(Copy, Clone, PartialEq)] +enum USARTStateTX { + Idle, + Transmitting, + Aborted(Result<(), ErrorCode>), +} + +pub struct Usart<'a> { + registers: StaticRef, + clock: UsartClock<'a>, + + tx_client: OptionalCell<&'a dyn hil::uart::TransmitClient>, + rx_client: OptionalCell<&'a dyn hil::uart::ReceiveClient>, + + tx_buffer: TakeCell<'static, [u8]>, + tx_len: Cell, + tx_index: Cell, + + rx_buffer: TakeCell<'static, [u8]>, + rx_len: Cell, + rx_index: Cell, + + usart_tx_state: Cell, + usart_rx_state: Cell, + + deferred_call: DeferredCall, +} + +impl<'a> Usart<'a> { + pub fn new_usart1(clocks: &'a dyn Stm32l4Clocks) -> Self { + usart_new!( + USART1_BASE, + phclk::PeripheralClockType::APB2(phclk::PCLK2::USART1), + clocks + ) + } + + pub fn new_usart2(clocks: &'a dyn Stm32l4Clocks) -> Self { + usart_new!( + USART2_BASE, + phclk::PeripheralClockType::APB1(phclk::PCLK1::USART2), + clocks + ) + } + + pub fn new_usart3(clocks: &'a dyn Stm32l4Clocks) -> Self { + usart_new!( + USART3_BASE, + phclk::PeripheralClockType::APB1(phclk::PCLK1::USART3), + clocks + ) + } + + pub fn is_enabled_clock(&self) -> bool { + self.clock.is_enabled() + } + + pub fn enable_clock(&self) { + self.clock.enable(); + } + + pub fn disable_clock(&self) { + self.clock.disable(); + } + + pub fn handle_interrupt(&self) { + // TXE interrupt - transmit data register empty + if self.registers.isr.is_set(ISR::TXE) + && self.usart_tx_state.get() == USARTStateTX::Transmitting + { + let index = self.tx_index.get(); + let len = self.tx_len.get(); + + if index < len { + self.tx_buffer.map(|buf| { + self.registers.tdr.set(buf[index] as u32); + }); + self.tx_index.set(index + 1); + + // If last byte, disable TXE and enable TC interrupt + if index + 1 >= len { + self.registers.cr1.modify(CR1::TXEIE::CLEAR); + self.enable_transmit_complete_interrupt(); + } + } + } + + // TC interrupt - transmission complete + if self.registers.isr.is_set(ISR::TC) + && self.usart_tx_state.get() == USARTStateTX::Transmitting + { + self.clear_transmit_complete(); + self.disable_transmit_complete_interrupt(); + self.usart_tx_state.set(USARTStateTX::Idle); + + let len = self.tx_len.get(); + self.tx_len.set(0); + self.tx_index.set(0); + + self.tx_client.map(|client| { + self.tx_buffer.take().map(|buf| { + client.transmitted_buffer(buf, len, Ok(())); + }); + }); + } + + // RXNE interrupt - receive data register not empty + if self.registers.isr.is_set(ISR::RXNE) + && self.usart_rx_state.get() == USARTStateRX::Receiving + { + let index = self.rx_index.get(); + let len = self.rx_len.get(); + + if index < len { + let data = self.registers.rdr.get() as u8; + self.rx_buffer.map(|buf| { + buf[index] = data; + }); + self.rx_index.set(index + 1); + + // If buffer full, complete reception + if index + 1 >= len { + self.registers.cr1.modify(CR1::RXNEIE::CLEAR); + self.disable_error_interrupt(); + self.usart_rx_state.set(USARTStateRX::Idle); + + self.rx_len.set(0); + self.rx_index.set(0); + + self.rx_client.map(|client| { + self.rx_buffer.take().map(|buf| { + client.received_buffer(buf, len, Ok(()), hil::uart::Error::None); + }); + }); + } + } + } + + // Error handling - must come before RXNE to clear errors first + if self.is_enabled_error_interrupt() { + let isr = self.registers.isr.get(); + + // Check for framing error + if (isr & (1 << 1)) != 0 { + self.registers.icr.write(ICR::FECF::SET); + } + + // Check for noise error + if (isr & (1 << 2)) != 0 { + self.registers.icr.write(ICR::NECF::SET); + } + + // Check for overrun error + if (isr & (1 << 3)) != 0 { + self.registers.icr.write(ICR::ORECF::SET); + + if self.usart_rx_state.get() == USARTStateRX::Receiving { + self.registers.cr1.modify(CR1::RXNEIE::CLEAR); + self.disable_error_interrupt(); + self.usart_rx_state.set(USARTStateRX::Idle); + + let count = self.rx_index.get(); + self.rx_len.set(0); + self.rx_index.set(0); + + self.rx_client.map(|client| { + self.rx_buffer.take().map(|buf| { + client.received_buffer( + buf, + count, + Err(ErrorCode::CANCEL), + hil::uart::Error::OverrunError, + ); + }) + }); + } + } + } + } + + // for use by panic in io.rs + pub fn send_byte(&self, byte: u8) { + // Clear TC flag before starting + self.registers.icr.write(ICR::TCCF::SET); + + // Wait for TXE with timeout to avoid infinite loop + let mut timeout = 100000; + while !self.registers.isr.is_set(ISR::TXE) { + timeout -= 1; + if timeout == 0 { + return; // Timeout - skip this byte + } + } + + self.registers.tdr.set(byte.into()); + + // Wait for TC (transmission complete) to ensure byte is fully sent + timeout = 100000; + while !self.registers.isr.is_set(ISR::TC) { + timeout -= 1; + if timeout == 0 { + break; + } + } + } + + // enable interrupts for framing, overrun and noise errors + fn enable_error_interrupt(&self) { + self.registers.cr3.modify(CR3::EIE::SET); + } + + // disable interrupts for framing, overrun and noise errors + fn disable_error_interrupt(&self) { + self.registers.cr3.modify(CR3::EIE::CLEAR); + } + + // check if interrupts for framing, overrun and noise errors are enbaled + fn is_enabled_error_interrupt(&self) -> bool { + self.registers.cr3.is_set(CR3::EIE) + } + + fn enable_transmit_complete_interrupt(&self) { + self.registers.cr1.modify(CR1::TCIE::SET); + } + + fn disable_transmit_complete_interrupt(&self) { + self.registers.cr1.modify(CR1::TCIE::CLEAR); + } + + fn clear_transmit_complete(&self) { + // On L4, clear by writing 1 to ICR.TCCF + self.registers.icr.write(ICR::TCCF::SET); + } + + fn set_baud_rate(&self, baud_rate: u32) -> Result<(), ErrorCode> { + // USARTDIV calculation per RM0351 Section 40.5.4 (STM32L476) + // + // Baud rate calculation equation: + // + // OVER8 = 0 (16x oversampling): + // Tx/Rx baud = f_CK / USARTDIV + // BRR contains USARTDIV (16-bit value with 4-bit fraction [3:0], 12-bit mantissa [15:4]) + // + // OVER8 = 1 (8x oversampling): + // Tx/Rx baud = 2 * f_CK / USARTDIV + // BRR[2:0] = USARTDIV[3:0] >> 1 (only 3 fraction bits) + // BRR[3] must be 0 + // BRR[15:4] = USARTDIV[15:4] + + let pclk_freq = self.clock.0.get_frequency(); + + let brr_val = if (pclk_freq / 16) >= baud_rate { + // Use 16x oversampling (OVER8 = 0) + self.registers.cr1.modify(CR1::OVER8::CLEAR); + + // Calculate USARTDIV with 4-bit fraction: (f_CK * 16) / baud_rate + // Add baud_rate/2 for rounding + (pclk_freq + (baud_rate / 2)) / baud_rate + } else if (pclk_freq / 8) >= baud_rate { + // Use 8x oversampling (OVER8 = 1) + self.registers.cr1.modify(CR1::OVER8::SET); + + // Calculate USARTDIV with 4-bit fraction: (f_CK * 32) / baud_rate + let div = ((pclk_freq * 32) + (baud_rate / 2)) / baud_rate; + + // BRR encoding for OVER8=1: + // Mantissa [15:4] unchanged, fraction [3:0] >> 1 to [2:0], bit [3] = 0 + let mantissa = div & 0xFFF0; + let fraction = (div & 0x000F) >> 1; + mantissa | fraction + } else { + return Err(ErrorCode::INVAL); + }; + + self.registers.brr.modify(BRR::BRR.val(brr_val)); + Ok(()) + } + + // try to disable the USART and return BUSY if a transfer is taking place + pub fn disable(&self) -> Result<(), ErrorCode> { + if self.usart_tx_state.get() == USARTStateTX::Transmitting + || self.usart_rx_state.get() == USARTStateRX::Receiving + { + Err(ErrorCode::BUSY) + } else { + self.registers.cr1.modify(CR1::UE::CLEAR); + Ok(()) + } + } +} + +impl<'a> DeferredCallClient for Usart<'a> { + fn register(&'static self) { + self.deferred_call.register(self); + } + + fn handle_deferred_call(&self) { + if let USARTStateTX::Aborted(rcode) = self.usart_tx_state.get() { + self.tx_client.map(|client| { + self.tx_buffer.take().map(|buf| { + client.transmitted_buffer(buf, self.tx_index.get(), rcode); + }); + }); + self.usart_tx_state.set(USARTStateTX::Idle); + } + + if let USARTStateRX::Aborted(rcode, error) = self.usart_rx_state.get() { + self.rx_client.map(|client| { + self.rx_buffer.take().map(|buf| { + client.received_buffer(buf, self.rx_index.get(), rcode, error); + }); + }); + self.usart_rx_state.set(USARTStateRX::Idle); + } + } +} + +impl<'a> hil::uart::Transmit<'a> for Usart<'a> { + fn set_transmit_client(&self, client: &'a dyn hil::uart::TransmitClient) { + self.tx_client.set(client); + } + + fn transmit_buffer( + &self, + tx_data: &'static mut [u8], + tx_len: usize, + ) -> Result<(), (ErrorCode, &'static mut [u8])> { + if self.usart_tx_state.get() != USARTStateTX::Idle { + return Err((ErrorCode::BUSY, tx_data)); + } + + self.tx_buffer.replace(tx_data); + self.tx_len.set(tx_len); + self.tx_index.set(0); + + self.usart_tx_state.set(USARTStateTX::Transmitting); + + // Enable TXE interrupt + self.registers.cr1.modify(CR1::TXEIE::SET); + Ok(()) + } + + fn transmit_word(&self, _word: u32) -> Result<(), ErrorCode> { + Err(ErrorCode::FAIL) + } + + fn transmit_abort(&self) -> Result<(), ErrorCode> { + if self.usart_tx_state.get() != USARTStateTX::Idle { + self.registers.cr1.modify(CR1::TXEIE::CLEAR); + self.usart_tx_state + .set(USARTStateTX::Aborted(Err(ErrorCode::CANCEL))); + self.deferred_call.set(); + Err(ErrorCode::BUSY) + } else { + Ok(()) + } + } +} + +impl<'a> hil::uart::Configure for Usart<'a> { + fn configure(&self, params: hil::uart::Parameters) -> Result<(), ErrorCode> { + if params.stop_bits != hil::uart::StopBits::One + || params.parity != hil::uart::Parity::None + || params.hw_flow_control + || params.width != hil::uart::Width::Eight + { + panic!("Currently we only support uart setting of 8N1, no hardware flow control"); + } + + // Configure the word length - 0: 1 Start bit, 8 Data bits, n Stop bits + self.registers.cr1.modify(CR1::M0::CLEAR); + self.registers.cr1.modify(CR1::M1::CLEAR); + + // Set the stop bit length - 00: 1 Stop bits + self.registers.cr2.modify(CR2::STOP.val(0b00_u32)); + + // Set no parity + self.registers.cr1.modify(CR1::PCE::CLEAR); + + self.set_baud_rate(params.baud_rate)?; + + // Enable transmit block + self.registers.cr1.modify(CR1::TE::SET); + + // Enable receive block + self.registers.cr1.modify(CR1::RE::SET); + + // Enable USART + self.registers.cr1.modify(CR1::UE::SET); + + Ok(()) + } +} + +impl<'a> hil::uart::Receive<'a> for Usart<'a> { + fn set_receive_client(&self, client: &'a dyn hil::uart::ReceiveClient) { + self.rx_client.set(client); + } + + fn receive_buffer( + &self, + rx_buffer: &'static mut [u8], + rx_len: usize, + ) -> Result<(), (ErrorCode, &'static mut [u8])> { + if self.usart_rx_state.get() != USARTStateRX::Idle { + return Err((ErrorCode::BUSY, rx_buffer)); + } + + if rx_len > rx_buffer.len() { + return Err((ErrorCode::SIZE, rx_buffer)); + } + + self.rx_buffer.replace(rx_buffer); + self.rx_len.set(rx_len); + self.rx_index.set(0); + + self.usart_rx_state.set(USARTStateRX::Receiving); + + self.enable_error_interrupt(); + + // Enable RXNE interrupt + self.registers.cr1.modify(CR1::RXNEIE::SET); + Ok(()) + } + + fn receive_word(&self) -> Result<(), ErrorCode> { + Err(ErrorCode::FAIL) + } + + fn receive_abort(&self) -> Result<(), ErrorCode> { + if self.usart_rx_state.get() != USARTStateRX::Idle { + self.registers.cr1.modify(CR1::RXNEIE::CLEAR); + self.disable_error_interrupt(); + self.usart_rx_state.set(USARTStateRX::Aborted( + Err(ErrorCode::CANCEL), + hil::uart::Error::Aborted, + )); + self.deferred_call.set(); + Err(ErrorCode::BUSY) + } else { + Ok(()) + } + } +} + +struct UsartClock<'a>(phclk::PeripheralClock<'a>); + +impl ClockInterface for UsartClock<'_> { + fn is_enabled(&self) -> bool { + self.0.is_enabled() + } + + fn enable(&self) { + self.0.enable(); + } + + fn disable(&self) { + self.0.disable(); + } +}