diff --git a/ci.sh b/ci.sh
index 3322c60d1..6a5e6e3f5 100755
--- a/ci.sh
+++ b/ci.sh
@@ -67,6 +67,9 @@ cargo batch  \
     --- build --release --manifest-path embassy-nrf/Cargo.toml --target thumbv7em-none-eabi --features nrf52840,gpiote,defmt,time \
     --- build --release --manifest-path embassy-nrf/Cargo.toml --target thumbv7em-none-eabi --features nrf52840,gpiote,defmt,time-driver-rtc1 \
     --- build --release --manifest-path embassy-nrf/Cargo.toml --target thumbv7em-none-eabi --features nrf52840,gpiote,defmt,time,time-driver-rtc1 \
+    --- build --release --manifest-path embassy-nrf/Cargo.toml --target thumbv6m-none-eabi --features nrf51,defmt,time,time-driver-rtc1 \
+    --- build --release --manifest-path embassy-nrf/Cargo.toml --target thumbv6m-none-eabi --features nrf51,defmt,time \
+    --- build --release --manifest-path embassy-nrf/Cargo.toml --target thumbv6m-none-eabi --features nrf51,time \
     --- build --release --manifest-path embassy-rp/Cargo.toml --target thumbv6m-none-eabi --features time-driver,defmt \
     --- build --release --manifest-path embassy-rp/Cargo.toml --target thumbv6m-none-eabi --features time-driver,log \
     --- build --release --manifest-path embassy-rp/Cargo.toml --target thumbv6m-none-eabi --features time-driver,intrinsics \
@@ -148,6 +151,7 @@ cargo batch  \
     --- build --release --manifest-path examples/nrf52840/Cargo.toml --target thumbv7em-none-eabi --out-dir out/examples/nrf52840 \
     --- build --release --manifest-path examples/nrf5340/Cargo.toml --target thumbv8m.main-none-eabihf --out-dir out/examples/nrf5340 \
     --- build --release --manifest-path examples/nrf9160/Cargo.toml --target thumbv8m.main-none-eabihf --out-dir out/examples/nrf9160 \
+    --- build --release --manifest-path examples/nrf51/Cargo.toml --target thumbv6m-none-eabi --out-dir out/examples/nrf51 \
     --- build --release --manifest-path examples/rp/Cargo.toml --target thumbv6m-none-eabi --out-dir out/examples/rp \
     --- build --release --manifest-path examples/stm32f0/Cargo.toml --target thumbv6m-none-eabi --out-dir out/examples/stm32f0 \
     --- build --release --manifest-path examples/stm32f1/Cargo.toml --target thumbv7m-none-eabi --out-dir out/examples/stm32f1 \
@@ -211,7 +215,8 @@ cargo batch  \
     --- build --release --manifest-path tests/stm32/Cargo.toml --target thumbv7em-none-eabi --features stm32l496zg --out-dir out/tests/stm32l496zg \
     --- build --release --manifest-path tests/stm32/Cargo.toml --target thumbv7em-none-eabi --features stm32wl55jc --out-dir out/tests/stm32wl55jc \
     --- build --release --manifest-path tests/rp/Cargo.toml --target thumbv6m-none-eabi --out-dir out/tests/rpi-pico \
-    --- build --release --manifest-path tests/nrf/Cargo.toml --target thumbv7em-none-eabi --out-dir out/tests/nrf52840-dk \
+    --- build --release --manifest-path tests/nrf52840/Cargo.toml --target thumbv7em-none-eabi --out-dir out/tests/nrf52840-dk \
+    --- build --release --manifest-path tests/nrf51422/Cargo.toml --target thumbv6m-none-eabi --out-dir out/tests/nrf51-dk \
     --- build --release --manifest-path tests/riscv32/Cargo.toml --target riscv32imac-unknown-none-elf \
     $BUILD_EXTRA
 
diff --git a/embassy-net/src/tcp.rs b/embassy-net/src/tcp.rs
index 72b0677b4..c508ff97a 100644
--- a/embassy-net/src/tcp.rs
+++ b/embassy-net/src/tcp.rs
@@ -342,7 +342,7 @@ impl<'a> TcpSocket<'a> {
         self.io.with(|s, _| s.may_send())
     }
 
-    /// return whether the recieve half of the full-duplex connection is open.
+    /// return whether the receive half of the full-duplex connection is open.
     /// This function returns true if it’s possible to receive data from the remote endpoint.
     /// It will return true while there is data in the receive buffer, and if there isn’t,
     /// as long as the remote endpoint has not closed the connection.
@@ -471,7 +471,7 @@ impl<'d> TcpIo<'d> {
                         s.register_recv_waker(cx.waker());
                         Poll::Pending
                     } else {
-                        // if we can't receive because the recieve half of the duplex connection is closed then return an error
+                        // if we can't receive because the receive half of the duplex connection is closed then return an error
                         Poll::Ready(Err(Error::ConnectionReset))
                     }
                 } else {
diff --git a/embassy-nrf/Cargo.toml b/embassy-nrf/Cargo.toml
index 10f268b51..a682e1227 100644
--- a/embassy-nrf/Cargo.toml
+++ b/embassy-nrf/Cargo.toml
@@ -15,6 +15,7 @@ src_base_git = "https://github.com/embassy-rs/embassy/blob/$COMMIT/embassy-nrf/s
 
 features = ["time", "defmt", "unstable-pac", "gpiote", "time-driver-rtc1"]
 flavors = [
+    { regex_feature = "nrf51", target = "thumbv6m-none-eabi" },
     { regex_feature = "nrf52.*", target = "thumbv7em-none-eabihf" },
     { regex_feature = "nrf53.*", target = "thumbv8m.main-none-eabihf" },
     { regex_feature = "nrf91.*", target = "thumbv8m.main-none-eabihf" },
@@ -28,6 +29,7 @@ rustdoc-args = ["--cfg", "docsrs"]
 default = ["rt"]
 ## Cortex-M runtime (enabled by default)
 rt = [
+    "nrf51-pac?/rt",
     "nrf52805-pac?/rt",
     "nrf52810-pac?/rt",
     "nrf52811-pac?/rt",
@@ -71,6 +73,8 @@ reset-pin-as-gpio = []
 qspi-multiwrite-flash = []
 
 #! ### Chip selection features
+## nRF51
+nrf51 = ["nrf51-pac", "_nrf51"]
 ## nRF52805
 nrf52805 = ["nrf52805-pac", "_nrf52"]
 ## nRF52810
@@ -104,6 +108,7 @@ _nrf5340-net = ["_nrf5340", "nrf5340-net-pac"]
 _nrf5340 = ["_gpio-p1", "_dppi"]
 _nrf9160 = ["nrf9160-pac", "_dppi"]
 _nrf52 = ["_ppi"]
+_nrf51 = ["_ppi"]
 
 _time-driver = ["dep:embassy-time-driver", "embassy-time-driver?/tick-hz-32_768"]
 
@@ -144,6 +149,7 @@ embedded-storage-async = "0.4.0"
 cfg-if = "1.0.0"
 document-features = "0.2.7"
 
+nrf51-pac = { version = "0.12.0", optional = true }
 nrf52805-pac = { version = "0.12.0", optional = true }
 nrf52810-pac = { version = "0.12.0", optional = true }
 nrf52811-pac = { version = "0.12.0", optional = true }
diff --git a/embassy-nrf/README.md b/embassy-nrf/README.md
index 50662749d..3df5f1fa5 100644
--- a/embassy-nrf/README.md
+++ b/embassy-nrf/README.md
@@ -14,11 +14,12 @@ For a complete list of available peripherals and features, see the [embassy-nrf
 
 The `embassy-nrf` HAL supports most variants of the nRF family:
 
+* nRF51 ([examples](https://github.com/embassy-rs/embassy/tree/main/examples/nrf51))
 * nRF52 ([examples](https://github.com/embassy-rs/embassy/tree/main/examples/nrf52840))
 * nRF53 ([examples](https://github.com/embassy-rs/embassy/tree/main/examples/nrf5340))
 * nRF91 ([examples](https://github.com/embassy-rs/embassy/tree/main/examples/nrf9160))
 
-Most peripherals are supported. To check what's available, make sure to pick the MCU you're targeting in the top menu in the [documentation](https://docs.embassy.dev/embassy-nrf).
+Most peripherals are supported, but can vary between chip families. To check what's available, make sure to pick the MCU you're targeting in the top menu in the [documentation](https://docs.embassy.dev/embassy-nrf).
 
 For MCUs with TrustZone support, both Secure (S) and Non-Secure (NS) modes are supported. Running in Secure mode
 allows running Rust code without a SPM or TF-M binary, saving flash space and simplifying development.
diff --git a/embassy-nrf/src/chips/nrf51.rs b/embassy-nrf/src/chips/nrf51.rs
new file mode 100644
index 000000000..016352fb8
--- /dev/null
+++ b/embassy-nrf/src/chips/nrf51.rs
@@ -0,0 +1,169 @@
+pub use nrf51_pac as pac;
+
+/// The maximum buffer size that the EasyDMA can send/recv in one operation.
+pub const EASY_DMA_SIZE: usize = (1 << 14) - 1;
+
+pub const FLASH_SIZE: usize = 128 * 1024;
+
+embassy_hal_internal::peripherals! {
+    // RTC
+    RTC0,
+    RTC1,
+
+    // WDT
+    WDT,
+
+    // NVMC
+    NVMC,
+
+    // RNG
+    RNG,
+
+    // UARTE
+    UART0,
+
+    // SPI/TWI
+    TWI0,
+    SPI0,
+
+    // ADC
+    ADC,
+
+    // TIMER
+    TIMER0,
+    TIMER1,
+    TIMER2,
+
+    // GPIOTE
+    GPIOTE_CH0,
+    GPIOTE_CH1,
+    GPIOTE_CH2,
+    GPIOTE_CH3,
+
+    // PPI
+    PPI_CH0,
+    PPI_CH1,
+    PPI_CH2,
+    PPI_CH3,
+    PPI_CH4,
+    PPI_CH5,
+    PPI_CH6,
+    PPI_CH7,
+    PPI_CH8,
+    PPI_CH9,
+    PPI_CH10,
+    PPI_CH11,
+    PPI_CH12,
+    PPI_CH13,
+    PPI_CH14,
+    PPI_CH15,
+
+    PPI_GROUP0,
+    PPI_GROUP1,
+    PPI_GROUP2,
+    PPI_GROUP3,
+
+    // GPIO port 0
+    P0_00,
+    P0_01,
+    P0_02,
+    P0_03,
+    P0_04,
+    P0_05,
+    P0_06,
+    P0_07,
+    P0_08,
+    P0_09,
+    P0_10,
+    P0_11,
+    P0_12,
+    P0_13,
+    P0_14,
+    P0_15,
+    P0_16,
+    P0_17,
+    P0_18,
+    P0_19,
+    P0_20,
+    P0_21,
+    P0_22,
+    P0_23,
+    P0_24,
+    P0_25,
+    P0_26,
+    P0_27,
+    P0_28,
+    P0_29,
+    P0_30,
+    P0_31,
+
+    // TEMP
+    TEMP,
+}
+
+impl_timer!(TIMER0, TIMER0, TIMER0);
+impl_timer!(TIMER1, TIMER1, TIMER1);
+impl_timer!(TIMER2, TIMER2, TIMER2);
+
+impl_rng!(RNG, RNG, RNG);
+
+impl_pin!(P0_00, 0, 0);
+impl_pin!(P0_01, 0, 1);
+impl_pin!(P0_02, 0, 2);
+impl_pin!(P0_03, 0, 3);
+impl_pin!(P0_04, 0, 4);
+impl_pin!(P0_05, 0, 5);
+impl_pin!(P0_06, 0, 6);
+impl_pin!(P0_07, 0, 7);
+impl_pin!(P0_08, 0, 8);
+impl_pin!(P0_09, 0, 9);
+impl_pin!(P0_10, 0, 10);
+impl_pin!(P0_11, 0, 11);
+impl_pin!(P0_12, 0, 12);
+impl_pin!(P0_13, 0, 13);
+impl_pin!(P0_14, 0, 14);
+impl_pin!(P0_15, 0, 15);
+impl_pin!(P0_16, 0, 16);
+impl_pin!(P0_17, 0, 17);
+impl_pin!(P0_18, 0, 18);
+impl_pin!(P0_19, 0, 19);
+impl_pin!(P0_20, 0, 20);
+impl_pin!(P0_21, 0, 21);
+impl_pin!(P0_22, 0, 22);
+impl_pin!(P0_23, 0, 23);
+impl_pin!(P0_24, 0, 24);
+impl_pin!(P0_25, 0, 25);
+impl_pin!(P0_26, 0, 26);
+impl_pin!(P0_27, 0, 27);
+impl_pin!(P0_28, 0, 28);
+impl_pin!(P0_29, 0, 29);
+impl_pin!(P0_30, 0, 30);
+impl_pin!(P0_31, 0, 31);
+
+embassy_hal_internal::interrupt_mod!(
+    POWER_CLOCK,
+    RADIO,
+    UART0,
+    SPI0_TWI0,
+    SPI1_TWI1,
+    GPIOTE,
+    ADC,
+    TIMER0,
+    TIMER1,
+    TIMER2,
+    RTC0,
+    TEMP,
+    RNG,
+    ECB,
+    CCM_AAR,
+    WDT,
+    RTC1,
+    QDEC,
+    LPCOMP,
+    SWI0,
+    SWI1,
+    SWI2,
+    SWI3,
+    SWI4,
+    SWI5,
+);
diff --git a/embassy-nrf/src/gpio.rs b/embassy-nrf/src/gpio.rs
index 287811e61..b2f987109 100644
--- a/embassy-nrf/src/gpio.rs
+++ b/embassy-nrf/src/gpio.rs
@@ -8,7 +8,13 @@ use cfg_if::cfg_if;
 use embassy_hal_internal::{impl_peripheral, into_ref, PeripheralRef};
 
 use self::sealed::Pin as _;
+#[cfg(feature = "nrf51")]
+use crate::pac::gpio;
+#[cfg(feature = "nrf51")]
+use crate::pac::gpio::pin_cnf::{DRIVE_A, PULL_A};
+#[cfg(not(feature = "nrf51"))]
 use crate::pac::p0 as gpio;
+#[cfg(not(feature = "nrf51"))]
 use crate::pac::p0::pin_cnf::{DRIVE_A, PULL_A};
 use crate::{pac, Peripheral};
 
@@ -376,6 +382,9 @@ pub(crate) mod sealed {
         fn block(&self) -> &gpio::RegisterBlock {
             unsafe {
                 match self.pin_port() / 32 {
+                    #[cfg(feature = "nrf51")]
+                    0 => &*pac::GPIO::ptr(),
+                    #[cfg(not(feature = "nrf51"))]
                     0 => &*pac::P0::ptr(),
                     #[cfg(feature = "_gpio-p1")]
                     1 => &*pac::P1::ptr(),
@@ -478,6 +487,7 @@ impl<'a, P: Pin> PselBits for Option<PeripheralRef<'a, P>> {
     }
 }
 
+#[allow(dead_code)]
 pub(crate) fn deconfigure_pin(psel_bits: u32) {
     if psel_bits & 0x8000_0000 != 0 {
         return;
diff --git a/embassy-nrf/src/lib.rs b/embassy-nrf/src/lib.rs
index d9c92a76d..358a7cc27 100644
--- a/embassy-nrf/src/lib.rs
+++ b/embassy-nrf/src/lib.rs
@@ -40,6 +40,7 @@ pub(crate) mod util;
 #[cfg(feature = "_time-driver")]
 mod time_driver;
 
+#[cfg(not(feature = "nrf51"))]
 pub mod buffered_uarte;
 pub mod gpio;
 #[cfg(feature = "gpiote")]
@@ -58,7 +59,12 @@ pub mod nvmc;
 ))]
 pub mod pdm;
 pub mod ppi;
-#[cfg(not(any(feature = "nrf52805", feature = "nrf52820", feature = "_nrf5340-net")))]
+#[cfg(not(any(
+    feature = "nrf51",
+    feature = "nrf52805",
+    feature = "nrf52820",
+    feature = "_nrf5340-net"
+)))]
 pub mod pwm;
 #[cfg(not(any(feature = "nrf51", feature = "_nrf9160", feature = "_nrf5340-net")))]
 pub mod qdec;
@@ -66,15 +72,20 @@ pub mod qdec;
 pub mod qspi;
 #[cfg(not(any(feature = "_nrf5340-app", feature = "_nrf9160")))]
 pub mod rng;
-#[cfg(not(any(feature = "nrf52820", feature = "_nrf5340-net")))]
+#[cfg(not(any(feature = "nrf51", feature = "nrf52820", feature = "_nrf5340-net")))]
 pub mod saadc;
+#[cfg(not(feature = "nrf51"))]
 pub mod spim;
+#[cfg(not(feature = "nrf51"))]
 pub mod spis;
 #[cfg(not(any(feature = "_nrf5340", feature = "_nrf9160")))]
 pub mod temp;
 pub mod timer;
+#[cfg(not(feature = "nrf51"))]
 pub mod twim;
+#[cfg(not(feature = "nrf51"))]
 pub mod twis;
+#[cfg(not(feature = "nrf51"))]
 pub mod uarte;
 #[cfg(any(
     feature = "_nrf5340-app",
@@ -87,6 +98,7 @@ pub mod usb;
 pub mod wdt;
 
 // This mod MUST go last, so that it sees all the `impl_foo!` macros
+#[cfg_attr(feature = "nrf51", path = "chips/nrf51.rs")]
 #[cfg_attr(feature = "nrf52805", path = "chips/nrf52805.rs")]
 #[cfg_attr(feature = "nrf52810", path = "chips/nrf52810.rs")]
 #[cfg_attr(feature = "nrf52811", path = "chips/nrf52811.rs")]
@@ -324,6 +336,7 @@ mod consts {
     pub const APPROTECT_DISABLED: u32 = 0x0000_005a;
 }
 
+#[cfg(not(feature = "nrf51"))]
 #[derive(Debug, Copy, Clone, Eq, PartialEq)]
 #[cfg_attr(feature = "defmt", derive(defmt::Format))]
 enum WriteResult {
@@ -335,10 +348,12 @@ enum WriteResult {
     Failed,
 }
 
+#[cfg(not(feature = "nrf51"))]
 unsafe fn uicr_write(address: *mut u32, value: u32) -> WriteResult {
     uicr_write_masked(address, value, 0xFFFF_FFFF)
 }
 
+#[cfg(not(feature = "nrf51"))]
 unsafe fn uicr_write_masked(address: *mut u32, value: u32, mask: u32) -> WriteResult {
     let curr_val = address.read_volatile();
     if curr_val & mask == value & mask {
@@ -371,9 +386,11 @@ pub fn init(config: config::Config) -> Peripherals {
     // before doing anything important.
     let peripherals = Peripherals::take();
 
+    #[allow(unused_mut)]
     let mut needs_reset = false;
 
     // Setup debug protection.
+    #[cfg(not(feature = "nrf51"))]
     match config.debug {
         config::Debug::Allowed => {
             #[cfg(feature = "_nrf52")]
@@ -489,7 +506,7 @@ pub fn init(config: config::Config) -> Peripherals {
     }
 
     // Configure LFCLK.
-    #[cfg(not(any(feature = "_nrf5340", feature = "_nrf9160")))]
+    #[cfg(not(any(feature = "nrf51", feature = "_nrf5340", feature = "_nrf9160")))]
     match config.lfclk_source {
         config::LfclkSource::InternalRC => r.lfclksrc.write(|w| w.src().rc()),
         config::LfclkSource::Synthesized => r.lfclksrc.write(|w| w.src().synth()),
diff --git a/embassy-nrf/src/ppi/mod.rs b/embassy-nrf/src/ppi/mod.rs
index 5b4a64388..f5764b8b7 100644
--- a/embassy-nrf/src/ppi/mod.rs
+++ b/embassy-nrf/src/ppi/mod.rs
@@ -284,6 +284,7 @@ impl ConfigurableChannel for AnyConfigurableChannel {
     }
 }
 
+#[cfg(not(feature = "nrf51"))]
 macro_rules! impl_ppi_channel {
     ($type:ident, $number:expr) => {
         impl crate::ppi::sealed::Channel for peripherals::$type {}
diff --git a/embassy-nrf/src/ppi/ppi.rs b/embassy-nrf/src/ppi/ppi.rs
index 3e9e9fc81..8ff52ece3 100644
--- a/embassy-nrf/src/ppi/ppi.rs
+++ b/embassy-nrf/src/ppi/ppi.rs
@@ -1,6 +1,6 @@
 use embassy_hal_internal::into_ref;
 
-use super::{Channel, ConfigurableChannel, Event, Ppi, StaticChannel, Task};
+use super::{Channel, ConfigurableChannel, Event, Ppi, Task};
 use crate::{pac, Peripheral};
 
 impl<'d> Task<'d> {
@@ -19,7 +19,7 @@ pub(crate) fn regs() -> &'static pac::ppi::RegisterBlock {
 }
 
 #[cfg(not(feature = "nrf51"))] // Not for nrf51 because of the fork task
-impl<'d, C: StaticChannel> Ppi<'d, C, 0, 1> {
+impl<'d, C: super::StaticChannel> Ppi<'d, C, 0, 1> {
     /// Configure PPI channel to trigger `task`.
     pub fn new_zero_to_one(ch: impl Peripheral<P = C> + 'd, task: Task) -> Self {
         into_ref!(ch);
@@ -84,6 +84,7 @@ impl<'d, C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize> Drop for
         let n = self.ch.number();
         r.ch[n].eep.write(|w| unsafe { w.bits(0) });
         r.ch[n].tep.write(|w| unsafe { w.bits(0) });
+        #[cfg(not(feature = "nrf51"))]
         r.fork[n].tep.write(|w| unsafe { w.bits(0) });
     }
 }
diff --git a/embassy-nrf/src/rng.rs b/embassy-nrf/src/rng.rs
index e2803f0d3..40b73231b 100644
--- a/embassy-nrf/src/rng.rs
+++ b/embassy-nrf/src/rng.rs
@@ -5,12 +5,10 @@
 use core::future::poll_fn;
 use core::marker::PhantomData;
 use core::ptr;
-use core::sync::atomic::{AtomicPtr, Ordering};
 use core::task::Poll;
 
 use embassy_hal_internal::drop::OnDrop;
 use embassy_hal_internal::{into_ref, PeripheralRef};
-use embassy_sync::waitqueue::AtomicWaker;
 
 use crate::interrupt::typelevel::Interrupt;
 use crate::{interrupt, Peripheral};
@@ -22,7 +20,6 @@ pub struct InterruptHandler<T: Instance> {
 
 impl<T: Instance> interrupt::typelevel::Handler<T::Interrupt> for InterruptHandler<T> {
     unsafe fn on_interrupt() {
-        let s = T::state();
         let r = T::regs();
 
         // Clear the event.
@@ -30,46 +27,25 @@ impl<T: Instance> interrupt::typelevel::Handler<T::Interrupt> for InterruptHandl
 
         // Mutate the slice within a critical section,
         // so that the future isn't dropped in between us loading the pointer and actually dereferencing it.
-        let (ptr, end) = critical_section::with(|_| {
-            let ptr = s.ptr.load(Ordering::Relaxed);
+        critical_section::with(|cs| {
+            let mut state = T::state().borrow_mut(cs);
             // We need to make sure we haven't already filled the whole slice,
             // in case the interrupt fired again before the executor got back to the future.
-            let end = s.end.load(Ordering::Relaxed);
-            if !ptr.is_null() && ptr != end {
+            if !state.ptr.is_null() && state.ptr != state.end {
                 // If the future was dropped, the pointer would have been set to null,
                 // so we're still good to mutate the slice.
                 // The safety contract of `Rng::new` means that the future can't have been dropped
                 // without calling its destructor.
                 unsafe {
-                    *ptr = r.value.read().value().bits();
+                    *state.ptr = r.value.read().value().bits();
+                    state.ptr = state.ptr.add(1);
+                }
+
+                if state.ptr == state.end {
+                    state.waker.wake();
                 }
             }
-            (ptr, end)
         });
-
-        if ptr.is_null() || ptr == end {
-            // If the future was dropped, there's nothing to do.
-            // If `ptr == end`, we were called by mistake, so return.
-            return;
-        }
-
-        let new_ptr = unsafe { ptr.add(1) };
-        match s
-            .ptr
-            .compare_exchange(ptr, new_ptr, Ordering::Relaxed, Ordering::Relaxed)
-        {
-            Ok(_) => {
-                let end = s.end.load(Ordering::Relaxed);
-                // It doesn't matter if `end` was changed under our feet, because then this will just be false.
-                if new_ptr == end {
-                    s.waker.wake();
-                }
-            }
-            Err(_) => {
-                // If the future was dropped or finished, there's no point trying to wake it.
-                // It will have already stopped the RNG, so there's no need to do that either.
-            }
-        }
     }
 }
 
@@ -136,13 +112,14 @@ impl<'d, T: Instance> Rng<'d, T> {
             return; // Nothing to fill
         }
 
-        let s = T::state();
-
         let range = dest.as_mut_ptr_range();
         // Even if we've preempted the interrupt, it can't preempt us again,
         // so we don't need to worry about the order we write these in.
-        s.ptr.store(range.start, Ordering::Relaxed);
-        s.end.store(range.end, Ordering::Relaxed);
+        critical_section::with(|cs| {
+            let mut state = T::state().borrow_mut(cs);
+            state.ptr = range.start;
+            state.end = range.end;
+        });
 
         self.enable_irq();
         self.start();
@@ -151,24 +128,24 @@ impl<'d, T: Instance> Rng<'d, T> {
             self.stop();
             self.disable_irq();
 
-            // The interrupt is now disabled and can't preempt us anymore, so the order doesn't matter here.
-            s.ptr.store(ptr::null_mut(), Ordering::Relaxed);
-            s.end.store(ptr::null_mut(), Ordering::Relaxed);
+            critical_section::with(|cs| {
+                let mut state = T::state().borrow_mut(cs);
+                state.ptr = ptr::null_mut();
+                state.end = ptr::null_mut();
+            });
         });
 
         poll_fn(|cx| {
-            s.waker.register(cx.waker());
-
-            // The interrupt will never modify `end`, so load it first and then get the most up-to-date `ptr`.
-            let end = s.end.load(Ordering::Relaxed);
-            let ptr = s.ptr.load(Ordering::Relaxed);
-
-            if ptr == end {
-                // We're done.
-                Poll::Ready(())
-            } else {
-                Poll::Pending
-            }
+            critical_section::with(|cs| {
+                let mut s = T::state().borrow_mut(cs);
+                s.waker.register(cx.waker());
+                if s.ptr == s.end {
+                    // We're done.
+                    Poll::Ready(())
+                } else {
+                    Poll::Pending
+                }
+            })
         })
         .await;
 
@@ -194,9 +171,11 @@ impl<'d, T: Instance> Rng<'d, T> {
 impl<'d, T: Instance> Drop for Rng<'d, T> {
     fn drop(&mut self) {
         self.stop();
-        let s = T::state();
-        s.ptr.store(ptr::null_mut(), Ordering::Relaxed);
-        s.end.store(ptr::null_mut(), Ordering::Relaxed);
+        critical_section::with(|cs| {
+            let mut state = T::state().borrow_mut(cs);
+            state.ptr = ptr::null_mut();
+            state.end = ptr::null_mut();
+        });
     }
 }
 
@@ -227,21 +206,48 @@ impl<'d, T: Instance> rand_core::RngCore for Rng<'d, T> {
 impl<'d, T: Instance> rand_core::CryptoRng for Rng<'d, T> {}
 
 pub(crate) mod sealed {
+    use core::cell::{Ref, RefCell, RefMut};
+
+    use critical_section::{CriticalSection, Mutex};
+    use embassy_sync::waitqueue::WakerRegistration;
+
     use super::*;
 
     /// Peripheral static state
     pub struct State {
-        pub ptr: AtomicPtr<u8>,
-        pub end: AtomicPtr<u8>,
-        pub waker: AtomicWaker,
+        inner: Mutex<RefCell<InnerState>>,
     }
 
+    pub struct InnerState {
+        pub ptr: *mut u8,
+        pub end: *mut u8,
+        pub waker: WakerRegistration,
+    }
+
+    unsafe impl Send for InnerState {}
+
     impl State {
         pub const fn new() -> Self {
             Self {
-                ptr: AtomicPtr::new(ptr::null_mut()),
-                end: AtomicPtr::new(ptr::null_mut()),
-                waker: AtomicWaker::new(),
+                inner: Mutex::new(RefCell::new(InnerState::new())),
+            }
+        }
+
+        pub fn borrow<'cs>(&'cs self, cs: CriticalSection<'cs>) -> Ref<'cs, InnerState> {
+            self.inner.borrow(cs).borrow()
+        }
+
+        pub fn borrow_mut<'cs>(&'cs self, cs: CriticalSection<'cs>) -> RefMut<'cs, InnerState> {
+            self.inner.borrow(cs).borrow_mut()
+        }
+    }
+
+    impl InnerState {
+        pub const fn new() -> Self {
+            Self {
+                ptr: ptr::null_mut(),
+                end: ptr::null_mut(),
+                waker: WakerRegistration::new(),
             }
         }
     }
diff --git a/embassy-nrf/src/time_driver.rs b/embassy-nrf/src/time_driver.rs
index 042f7c5f7..3407c9504 100644
--- a/embassy-nrf/src/time_driver.rs
+++ b/embassy-nrf/src/time_driver.rs
@@ -171,7 +171,8 @@ impl RtcDriver {
     fn next_period(&self) {
         critical_section::with(|cs| {
             let r = rtc();
-            let period = self.period.fetch_add(1, Ordering::Relaxed) + 1;
+            let period = self.period.load(Ordering::Relaxed) + 1;
+            self.period.store(period, Ordering::Relaxed);
             let t = (period as u64) << 23;
 
             for n in 0..ALARM_COUNT {
@@ -219,18 +220,15 @@ impl Driver for RtcDriver {
     }
 
     unsafe fn allocate_alarm(&self) -> Option<AlarmHandle> {
-        let id = self.alarm_count.fetch_update(Ordering::AcqRel, Ordering::Acquire, |x| {
-            if x < ALARM_COUNT as u8 {
-                Some(x + 1)
+        critical_section::with(|_| {
+            let id = self.alarm_count.load(Ordering::Relaxed);
+            if id < ALARM_COUNT as u8 {
+                self.alarm_count.store(id + 1, Ordering::Relaxed);
+                Some(AlarmHandle::new(id))
             } else {
                 None
             }
-        });
-
-        match id {
-            Ok(id) => Some(AlarmHandle::new(id)),
-            Err(_) => None,
-        }
+        })
     }
 
     fn set_alarm_callback(&self, alarm: AlarmHandle, callback: fn(*mut ()), ctx: *mut ()) {
diff --git a/embassy-nrf/src/timer.rs b/embassy-nrf/src/timer.rs
index 3dbfdac42..3c35baee5 100644
--- a/embassy-nrf/src/timer.rs
+++ b/embassy-nrf/src/timer.rs
@@ -111,7 +111,7 @@ impl<'d, T: Instance> Timer<'d, T> {
         Self::new_inner(timer, true)
     }
 
-    fn new_inner(timer: impl Peripheral<P = T> + 'd, is_counter: bool) -> Self {
+    fn new_inner(timer: impl Peripheral<P = T> + 'd, _is_counter: bool) -> Self {
         into_ref!(timer);
 
         let regs = T::regs();
@@ -122,12 +122,16 @@ impl<'d, T: Instance> Timer<'d, T> {
         // since changing BITMODE while running can cause 'unpredictable behaviour' according to the specification.
         this.stop();
 
-        if is_counter {
+        #[cfg(not(feature = "nrf51"))]
+        if _is_counter {
             regs.mode.write(|w| w.mode().low_power_counter());
         } else {
             regs.mode.write(|w| w.mode().timer());
         }
 
+        #[cfg(feature = "nrf51")]
+        regs.mode.write(|w| w.mode().timer());
+
         // Make the counter's max value as high as possible.
         // TODO: is there a reason someone would want to set this lower?
         regs.bitmode.write(|w| w.bitmode()._32bit());
@@ -238,7 +242,11 @@ pub struct Cc<'d, T: Instance> {
 impl<'d, T: Instance> Cc<'d, T> {
     /// Get the current value stored in the register.
     pub fn read(&self) -> u32 {
-        T::regs().cc[self.n].read().cc().bits()
+        #[cfg(not(feature = "nrf51"))]
+        return T::regs().cc[self.n].read().cc().bits();
+
+        #[cfg(feature = "nrf51")]
+        return T::regs().cc[self.n].read().bits();
     }
 
     /// Set the value stored in the register.
@@ -246,7 +254,11 @@ impl<'d, T: Instance> Cc<'d, T> {
     /// `event_compare` will fire when the timer's counter reaches this value.
     pub fn write(&self, value: u32) {
         // SAFETY: there are no invalid values for the CC register.
-        T::regs().cc[self.n].write(|w| unsafe { w.cc().bits(value) })
+        #[cfg(not(feature = "nrf51"))]
+        T::regs().cc[self.n].write(|w| unsafe { w.cc().bits(value) });
+
+        #[cfg(feature = "nrf51")]
+        T::regs().cc[self.n].write(|w| unsafe { w.bits(value) });
     }
 
     /// Capture the current value of the timer's counter in this register, and return it.
diff --git a/embassy-nrf/src/util.rs b/embassy-nrf/src/util.rs
index cd0f59490..b408c517b 100644
--- a/embassy-nrf/src/util.rs
+++ b/embassy-nrf/src/util.rs
@@ -1,3 +1,4 @@
+#![allow(dead_code)]
 use core::mem;
 
 const SRAM_LOWER: usize = 0x2000_0000;
diff --git a/embassy-stm32-wpan/Cargo.toml b/embassy-stm32-wpan/Cargo.toml
index 4f53a400a..360ca5f4b 100644
--- a/embassy-stm32-wpan/Cargo.toml
+++ b/embassy-stm32-wpan/Cargo.toml
@@ -44,6 +44,8 @@ defmt = ["dep:defmt", "embassy-sync/defmt", "embassy-embedded-hal/defmt", "embas
 ble = ["dep:stm32wb-hci"]
 mac = ["dep:bitflags", "dep:embassy-net-driver" ]
 
+extended = []
+
 stm32wb10cc = [ "embassy-stm32/stm32wb10cc" ]
 stm32wb15cc = [ "embassy-stm32/stm32wb15cc" ]
 stm32wb30ce = [ "embassy-stm32/stm32wb30ce" ]
diff --git a/embassy-stm32-wpan/build.rs b/embassy-stm32-wpan/build.rs
index 94aac070d..7ab458bf2 100644
--- a/embassy-stm32-wpan/build.rs
+++ b/embassy-stm32-wpan/build.rs
@@ -18,9 +18,22 @@ fn main() {
     // stm32wb tl_mbox link sections
 
     let out_file = out_dir.join("tl_mbox.x").to_string_lossy().to_string();
-    fs::write(out_file, fs::read_to_string("tl_mbox.x.in").unwrap()).unwrap();
+    let in_file;
+    if env::var_os("CARGO_FEATURE_EXTENDED").is_some() {
+        if env::vars()
+            .map(|(a, _)| a)
+            .any(|x| x.starts_with("CARGO_FEATURE_STM32WB1"))
+        {
+            in_file = "tl_mbox_extended_wb1.x.in";
+        } else {
+            in_file = "tl_mbox_extended_wbx5.x.in";
+        }
+    } else {
+        in_file = "tl_mbox.x.in";
+    }
+    fs::write(out_file, fs::read_to_string(in_file).unwrap()).unwrap();
     println!("cargo:rustc-link-search={}", out_dir.display());
-    println!("cargo:rerun-if-changed=tl_mbox.x.in");
+    println!("cargo:rerun-if-changed={}", in_file);
 }
 
 enum GetOneError {
diff --git a/embassy-stm32-wpan/tl_mbox_extended_wb1.x.in b/embassy-stm32-wpan/tl_mbox_extended_wb1.x.in
new file mode 100644
index 000000000..4cffdaddd
--- /dev/null
+++ b/embassy-stm32-wpan/tl_mbox_extended_wb1.x.in
@@ -0,0 +1,16 @@
+MEMORY 
+{
+    RAM_SHARED (xrw)           : ORIGIN = 0x20030000, LENGTH = 4K
+    RAMB_SHARED (xrw)          : ORIGIN = 0x20030028, LENGTH = 4K
+}
+
+/*
+ * Scatter the mailbox interface memory sections in shared memory
+ */
+SECTIONS
+{
+    TL_REF_TABLE                     (NOLOAD) : { *(TL_REF_TABLE) } >RAM_SHARED
+
+    MB_MEM1 (NOLOAD)                          : { *(MB_MEM1) } >RAMB_SHARED
+    MB_MEM2 (NOLOAD)                          : { _sMB_MEM2 = . ; *(MB_MEM2) ; _eMB_MEM2 = . ; } >RAMB_SHARED
+}
diff --git a/embassy-stm32-wpan/tl_mbox_extended_wbx5.x.in b/embassy-stm32-wpan/tl_mbox_extended_wbx5.x.in
new file mode 100644
index 000000000..281d637a9
--- /dev/null
+++ b/embassy-stm32-wpan/tl_mbox_extended_wbx5.x.in
@@ -0,0 +1,16 @@
+MEMORY 
+{
+    RAM_SHARED (xrw)           : ORIGIN = 0x20030000, LENGTH = 2K
+    RAMB_SHARED (xrw)          : ORIGIN = 0x20038000, LENGTH = 10K
+}
+
+/*
+ * Scatter the mailbox interface memory sections in shared memory
+ */
+SECTIONS
+{
+    TL_REF_TABLE                     (NOLOAD) : { *(TL_REF_TABLE) } >RAM_SHARED
+
+    MB_MEM1 (NOLOAD)                          : { *(MB_MEM1) } >RAMB_SHARED
+    MB_MEM2 (NOLOAD)                          : { _sMB_MEM2 = . ; *(MB_MEM2) ; _eMB_MEM2 = . ; } >RAMB_SHARED
+}
diff --git a/embassy-stm32/Cargo.toml b/embassy-stm32/Cargo.toml
index 00d8a5f63..698febf71 100644
--- a/embassy-stm32/Cargo.toml
+++ b/embassy-stm32/Cargo.toml
@@ -68,7 +68,7 @@ rand_core = "0.6.3"
 sdio-host = "0.5.0"
 critical-section = "1.1"
 #stm32-metapac = { version = "15" }
-stm32-metapac = { git = "https://github.com/embassy-rs/stm32-data-generated", tag = "stm32-data-aa5dbf859fae743306f5d816905f166de824241f" }
+stm32-metapac = { git = "https://github.com/embassy-rs/stm32-data-generated", tag = "stm32-data-0cb3a4fcaec702c93b3700715de796636d562b15" }
 vcell = "0.1.3"
 bxcan = "0.7.0"
 nb = "1.0.0"
@@ -80,6 +80,8 @@ chrono = { version = "^0.4", default-features = false, optional = true}
 bit_field = "0.10.2"
 document-features = "0.2.7"
 
+fdcan = { version = "0.2.0", optional = true }
+
 [dev-dependencies]
 critical-section = { version = "1.1", features = ["std"] }
 
@@ -87,7 +89,7 @@ critical-section = { version = "1.1", features = ["std"] }
 proc-macro2 = "1.0.36"
 quote = "1.0.15"
 #stm32-metapac = { version = "15", default-features = false, features = ["metadata"]}
-stm32-metapac = { git = "https://github.com/embassy-rs/stm32-data-generated", tag = "stm32-data-aa5dbf859fae743306f5d816905f166de824241f", default-features = false, features = ["metadata"]}
+stm32-metapac = { git = "https://github.com/embassy-rs/stm32-data-generated", tag = "stm32-data-0cb3a4fcaec702c93b3700715de796636d562b15", default-features = false, features = ["metadata"]}
 
 
 [features]
@@ -693,373 +695,373 @@ stm32f779ai = [ "stm32-metapac/stm32f779ai" ]
 stm32f779bi = [ "stm32-metapac/stm32f779bi" ]
 stm32f779ii = [ "stm32-metapac/stm32f779ii" ]
 stm32f779ni = [ "stm32-metapac/stm32f779ni" ]
-stm32g030c6 = [ "stm32-metapac/stm32g030c6" ]
-stm32g030c8 = [ "stm32-metapac/stm32g030c8" ]
-stm32g030f6 = [ "stm32-metapac/stm32g030f6" ]
-stm32g030j6 = [ "stm32-metapac/stm32g030j6" ]
-stm32g030k6 = [ "stm32-metapac/stm32g030k6" ]
-stm32g030k8 = [ "stm32-metapac/stm32g030k8" ]
-stm32g031c4 = [ "stm32-metapac/stm32g031c4" ]
-stm32g031c6 = [ "stm32-metapac/stm32g031c6" ]
-stm32g031c8 = [ "stm32-metapac/stm32g031c8" ]
-stm32g031f4 = [ "stm32-metapac/stm32g031f4" ]
-stm32g031f6 = [ "stm32-metapac/stm32g031f6" ]
-stm32g031f8 = [ "stm32-metapac/stm32g031f8" ]
-stm32g031g4 = [ "stm32-metapac/stm32g031g4" ]
-stm32g031g6 = [ "stm32-metapac/stm32g031g6" ]
-stm32g031g8 = [ "stm32-metapac/stm32g031g8" ]
-stm32g031j4 = [ "stm32-metapac/stm32g031j4" ]
-stm32g031j6 = [ "stm32-metapac/stm32g031j6" ]
-stm32g031k4 = [ "stm32-metapac/stm32g031k4" ]
-stm32g031k6 = [ "stm32-metapac/stm32g031k6" ]
-stm32g031k8 = [ "stm32-metapac/stm32g031k8" ]
-stm32g031y8 = [ "stm32-metapac/stm32g031y8" ]
-stm32g041c6 = [ "stm32-metapac/stm32g041c6" ]
-stm32g041c8 = [ "stm32-metapac/stm32g041c8" ]
-stm32g041f6 = [ "stm32-metapac/stm32g041f6" ]
-stm32g041f8 = [ "stm32-metapac/stm32g041f8" ]
-stm32g041g6 = [ "stm32-metapac/stm32g041g6" ]
-stm32g041g8 = [ "stm32-metapac/stm32g041g8" ]
-stm32g041j6 = [ "stm32-metapac/stm32g041j6" ]
-stm32g041k6 = [ "stm32-metapac/stm32g041k6" ]
-stm32g041k8 = [ "stm32-metapac/stm32g041k8" ]
-stm32g041y8 = [ "stm32-metapac/stm32g041y8" ]
-stm32g050c6 = [ "stm32-metapac/stm32g050c6" ]
-stm32g050c8 = [ "stm32-metapac/stm32g050c8" ]
-stm32g050f6 = [ "stm32-metapac/stm32g050f6" ]
-stm32g050k6 = [ "stm32-metapac/stm32g050k6" ]
-stm32g050k8 = [ "stm32-metapac/stm32g050k8" ]
-stm32g051c6 = [ "stm32-metapac/stm32g051c6" ]
-stm32g051c8 = [ "stm32-metapac/stm32g051c8" ]
-stm32g051f6 = [ "stm32-metapac/stm32g051f6" ]
-stm32g051f8 = [ "stm32-metapac/stm32g051f8" ]
-stm32g051g6 = [ "stm32-metapac/stm32g051g6" ]
-stm32g051g8 = [ "stm32-metapac/stm32g051g8" ]
-stm32g051k6 = [ "stm32-metapac/stm32g051k6" ]
-stm32g051k8 = [ "stm32-metapac/stm32g051k8" ]
-stm32g061c6 = [ "stm32-metapac/stm32g061c6" ]
-stm32g061c8 = [ "stm32-metapac/stm32g061c8" ]
-stm32g061f6 = [ "stm32-metapac/stm32g061f6" ]
-stm32g061f8 = [ "stm32-metapac/stm32g061f8" ]
-stm32g061g6 = [ "stm32-metapac/stm32g061g6" ]
-stm32g061g8 = [ "stm32-metapac/stm32g061g8" ]
-stm32g061k6 = [ "stm32-metapac/stm32g061k6" ]
-stm32g061k8 = [ "stm32-metapac/stm32g061k8" ]
-stm32g070cb = [ "stm32-metapac/stm32g070cb" ]
-stm32g070kb = [ "stm32-metapac/stm32g070kb" ]
-stm32g070rb = [ "stm32-metapac/stm32g070rb" ]
-stm32g071c6 = [ "stm32-metapac/stm32g071c6" ]
-stm32g071c8 = [ "stm32-metapac/stm32g071c8" ]
-stm32g071cb = [ "stm32-metapac/stm32g071cb" ]
-stm32g071eb = [ "stm32-metapac/stm32g071eb" ]
-stm32g071g6 = [ "stm32-metapac/stm32g071g6" ]
-stm32g071g8 = [ "stm32-metapac/stm32g071g8" ]
-stm32g071gb = [ "stm32-metapac/stm32g071gb" ]
-stm32g071k6 = [ "stm32-metapac/stm32g071k6" ]
-stm32g071k8 = [ "stm32-metapac/stm32g071k8" ]
-stm32g071kb = [ "stm32-metapac/stm32g071kb" ]
-stm32g071r6 = [ "stm32-metapac/stm32g071r6" ]
-stm32g071r8 = [ "stm32-metapac/stm32g071r8" ]
-stm32g071rb = [ "stm32-metapac/stm32g071rb" ]
-stm32g081cb = [ "stm32-metapac/stm32g081cb" ]
-stm32g081eb = [ "stm32-metapac/stm32g081eb" ]
-stm32g081gb = [ "stm32-metapac/stm32g081gb" ]
-stm32g081kb = [ "stm32-metapac/stm32g081kb" ]
-stm32g081rb = [ "stm32-metapac/stm32g081rb" ]
-stm32g0b0ce = [ "stm32-metapac/stm32g0b0ce" ]
-stm32g0b0ke = [ "stm32-metapac/stm32g0b0ke" ]
-stm32g0b0re = [ "stm32-metapac/stm32g0b0re" ]
-stm32g0b0ve = [ "stm32-metapac/stm32g0b0ve" ]
-stm32g0b1cb = [ "stm32-metapac/stm32g0b1cb" ]
-stm32g0b1cc = [ "stm32-metapac/stm32g0b1cc" ]
-stm32g0b1ce = [ "stm32-metapac/stm32g0b1ce" ]
-stm32g0b1kb = [ "stm32-metapac/stm32g0b1kb" ]
-stm32g0b1kc = [ "stm32-metapac/stm32g0b1kc" ]
-stm32g0b1ke = [ "stm32-metapac/stm32g0b1ke" ]
-stm32g0b1mb = [ "stm32-metapac/stm32g0b1mb" ]
-stm32g0b1mc = [ "stm32-metapac/stm32g0b1mc" ]
-stm32g0b1me = [ "stm32-metapac/stm32g0b1me" ]
-stm32g0b1ne = [ "stm32-metapac/stm32g0b1ne" ]
-stm32g0b1rb = [ "stm32-metapac/stm32g0b1rb" ]
-stm32g0b1rc = [ "stm32-metapac/stm32g0b1rc" ]
-stm32g0b1re = [ "stm32-metapac/stm32g0b1re" ]
-stm32g0b1vb = [ "stm32-metapac/stm32g0b1vb" ]
-stm32g0b1vc = [ "stm32-metapac/stm32g0b1vc" ]
-stm32g0b1ve = [ "stm32-metapac/stm32g0b1ve" ]
-stm32g0c1cc = [ "stm32-metapac/stm32g0c1cc" ]
-stm32g0c1ce = [ "stm32-metapac/stm32g0c1ce" ]
-stm32g0c1kc = [ "stm32-metapac/stm32g0c1kc" ]
-stm32g0c1ke = [ "stm32-metapac/stm32g0c1ke" ]
-stm32g0c1mc = [ "stm32-metapac/stm32g0c1mc" ]
-stm32g0c1me = [ "stm32-metapac/stm32g0c1me" ]
-stm32g0c1ne = [ "stm32-metapac/stm32g0c1ne" ]
-stm32g0c1rc = [ "stm32-metapac/stm32g0c1rc" ]
-stm32g0c1re = [ "stm32-metapac/stm32g0c1re" ]
-stm32g0c1vc = [ "stm32-metapac/stm32g0c1vc" ]
-stm32g0c1ve = [ "stm32-metapac/stm32g0c1ve" ]
-stm32g431c6 = [ "stm32-metapac/stm32g431c6" ]
-stm32g431c8 = [ "stm32-metapac/stm32g431c8" ]
-stm32g431cb = [ "stm32-metapac/stm32g431cb" ]
-stm32g431k6 = [ "stm32-metapac/stm32g431k6" ]
-stm32g431k8 = [ "stm32-metapac/stm32g431k8" ]
-stm32g431kb = [ "stm32-metapac/stm32g431kb" ]
-stm32g431m6 = [ "stm32-metapac/stm32g431m6" ]
-stm32g431m8 = [ "stm32-metapac/stm32g431m8" ]
-stm32g431mb = [ "stm32-metapac/stm32g431mb" ]
-stm32g431r6 = [ "stm32-metapac/stm32g431r6" ]
-stm32g431r8 = [ "stm32-metapac/stm32g431r8" ]
-stm32g431rb = [ "stm32-metapac/stm32g431rb" ]
-stm32g431v6 = [ "stm32-metapac/stm32g431v6" ]
-stm32g431v8 = [ "stm32-metapac/stm32g431v8" ]
-stm32g431vb = [ "stm32-metapac/stm32g431vb" ]
-stm32g441cb = [ "stm32-metapac/stm32g441cb" ]
-stm32g441kb = [ "stm32-metapac/stm32g441kb" ]
-stm32g441mb = [ "stm32-metapac/stm32g441mb" ]
-stm32g441rb = [ "stm32-metapac/stm32g441rb" ]
-stm32g441vb = [ "stm32-metapac/stm32g441vb" ]
-stm32g471cc = [ "stm32-metapac/stm32g471cc" ]
-stm32g471ce = [ "stm32-metapac/stm32g471ce" ]
-stm32g471mc = [ "stm32-metapac/stm32g471mc" ]
-stm32g471me = [ "stm32-metapac/stm32g471me" ]
-stm32g471qc = [ "stm32-metapac/stm32g471qc" ]
-stm32g471qe = [ "stm32-metapac/stm32g471qe" ]
-stm32g471rc = [ "stm32-metapac/stm32g471rc" ]
-stm32g471re = [ "stm32-metapac/stm32g471re" ]
-stm32g471vc = [ "stm32-metapac/stm32g471vc" ]
-stm32g471ve = [ "stm32-metapac/stm32g471ve" ]
-stm32g473cb = [ "stm32-metapac/stm32g473cb" ]
-stm32g473cc = [ "stm32-metapac/stm32g473cc" ]
-stm32g473ce = [ "stm32-metapac/stm32g473ce" ]
-stm32g473mb = [ "stm32-metapac/stm32g473mb" ]
-stm32g473mc = [ "stm32-metapac/stm32g473mc" ]
-stm32g473me = [ "stm32-metapac/stm32g473me" ]
-stm32g473pb = [ "stm32-metapac/stm32g473pb" ]
-stm32g473pc = [ "stm32-metapac/stm32g473pc" ]
-stm32g473pe = [ "stm32-metapac/stm32g473pe" ]
-stm32g473qb = [ "stm32-metapac/stm32g473qb" ]
-stm32g473qc = [ "stm32-metapac/stm32g473qc" ]
-stm32g473qe = [ "stm32-metapac/stm32g473qe" ]
-stm32g473rb = [ "stm32-metapac/stm32g473rb" ]
-stm32g473rc = [ "stm32-metapac/stm32g473rc" ]
-stm32g473re = [ "stm32-metapac/stm32g473re" ]
-stm32g473vb = [ "stm32-metapac/stm32g473vb" ]
-stm32g473vc = [ "stm32-metapac/stm32g473vc" ]
-stm32g473ve = [ "stm32-metapac/stm32g473ve" ]
-stm32g474cb = [ "stm32-metapac/stm32g474cb" ]
-stm32g474cc = [ "stm32-metapac/stm32g474cc" ]
-stm32g474ce = [ "stm32-metapac/stm32g474ce" ]
-stm32g474mb = [ "stm32-metapac/stm32g474mb" ]
-stm32g474mc = [ "stm32-metapac/stm32g474mc" ]
-stm32g474me = [ "stm32-metapac/stm32g474me" ]
-stm32g474pb = [ "stm32-metapac/stm32g474pb" ]
-stm32g474pc = [ "stm32-metapac/stm32g474pc" ]
-stm32g474pe = [ "stm32-metapac/stm32g474pe" ]
-stm32g474qb = [ "stm32-metapac/stm32g474qb" ]
-stm32g474qc = [ "stm32-metapac/stm32g474qc" ]
-stm32g474qe = [ "stm32-metapac/stm32g474qe" ]
-stm32g474rb = [ "stm32-metapac/stm32g474rb" ]
-stm32g474rc = [ "stm32-metapac/stm32g474rc" ]
-stm32g474re = [ "stm32-metapac/stm32g474re" ]
-stm32g474vb = [ "stm32-metapac/stm32g474vb" ]
-stm32g474vc = [ "stm32-metapac/stm32g474vc" ]
-stm32g474ve = [ "stm32-metapac/stm32g474ve" ]
-stm32g483ce = [ "stm32-metapac/stm32g483ce" ]
-stm32g483me = [ "stm32-metapac/stm32g483me" ]
-stm32g483pe = [ "stm32-metapac/stm32g483pe" ]
-stm32g483qe = [ "stm32-metapac/stm32g483qe" ]
-stm32g483re = [ "stm32-metapac/stm32g483re" ]
-stm32g483ve = [ "stm32-metapac/stm32g483ve" ]
-stm32g484ce = [ "stm32-metapac/stm32g484ce" ]
-stm32g484me = [ "stm32-metapac/stm32g484me" ]
-stm32g484pe = [ "stm32-metapac/stm32g484pe" ]
-stm32g484qe = [ "stm32-metapac/stm32g484qe" ]
-stm32g484re = [ "stm32-metapac/stm32g484re" ]
-stm32g484ve = [ "stm32-metapac/stm32g484ve" ]
-stm32g491cc = [ "stm32-metapac/stm32g491cc" ]
-stm32g491ce = [ "stm32-metapac/stm32g491ce" ]
-stm32g491kc = [ "stm32-metapac/stm32g491kc" ]
-stm32g491ke = [ "stm32-metapac/stm32g491ke" ]
-stm32g491mc = [ "stm32-metapac/stm32g491mc" ]
-stm32g491me = [ "stm32-metapac/stm32g491me" ]
-stm32g491rc = [ "stm32-metapac/stm32g491rc" ]
-stm32g491re = [ "stm32-metapac/stm32g491re" ]
-stm32g491vc = [ "stm32-metapac/stm32g491vc" ]
-stm32g491ve = [ "stm32-metapac/stm32g491ve" ]
-stm32g4a1ce = [ "stm32-metapac/stm32g4a1ce" ]
-stm32g4a1ke = [ "stm32-metapac/stm32g4a1ke" ]
-stm32g4a1me = [ "stm32-metapac/stm32g4a1me" ]
-stm32g4a1re = [ "stm32-metapac/stm32g4a1re" ]
-stm32g4a1ve = [ "stm32-metapac/stm32g4a1ve" ]
-stm32h503cb = [ "stm32-metapac/stm32h503cb" ]
-stm32h503eb = [ "stm32-metapac/stm32h503eb" ]
-stm32h503kb = [ "stm32-metapac/stm32h503kb" ]
-stm32h503rb = [ "stm32-metapac/stm32h503rb" ]
-stm32h562ag = [ "stm32-metapac/stm32h562ag" ]
-stm32h562ai = [ "stm32-metapac/stm32h562ai" ]
-stm32h562ig = [ "stm32-metapac/stm32h562ig" ]
-stm32h562ii = [ "stm32-metapac/stm32h562ii" ]
-stm32h562rg = [ "stm32-metapac/stm32h562rg" ]
-stm32h562ri = [ "stm32-metapac/stm32h562ri" ]
-stm32h562vg = [ "stm32-metapac/stm32h562vg" ]
-stm32h562vi = [ "stm32-metapac/stm32h562vi" ]
-stm32h562zg = [ "stm32-metapac/stm32h562zg" ]
-stm32h562zi = [ "stm32-metapac/stm32h562zi" ]
-stm32h563ag = [ "stm32-metapac/stm32h563ag" ]
-stm32h563ai = [ "stm32-metapac/stm32h563ai" ]
-stm32h563ig = [ "stm32-metapac/stm32h563ig" ]
-stm32h563ii = [ "stm32-metapac/stm32h563ii" ]
-stm32h563mi = [ "stm32-metapac/stm32h563mi" ]
-stm32h563rg = [ "stm32-metapac/stm32h563rg" ]
-stm32h563ri = [ "stm32-metapac/stm32h563ri" ]
-stm32h563vg = [ "stm32-metapac/stm32h563vg" ]
-stm32h563vi = [ "stm32-metapac/stm32h563vi" ]
-stm32h563zg = [ "stm32-metapac/stm32h563zg" ]
-stm32h563zi = [ "stm32-metapac/stm32h563zi" ]
-stm32h573ai = [ "stm32-metapac/stm32h573ai" ]
-stm32h573ii = [ "stm32-metapac/stm32h573ii" ]
-stm32h573mi = [ "stm32-metapac/stm32h573mi" ]
-stm32h573ri = [ "stm32-metapac/stm32h573ri" ]
-stm32h573vi = [ "stm32-metapac/stm32h573vi" ]
-stm32h573zi = [ "stm32-metapac/stm32h573zi" ]
-stm32h723ve = [ "stm32-metapac/stm32h723ve" ]
-stm32h723vg = [ "stm32-metapac/stm32h723vg" ]
-stm32h723ze = [ "stm32-metapac/stm32h723ze" ]
-stm32h723zg = [ "stm32-metapac/stm32h723zg" ]
-stm32h725ae = [ "stm32-metapac/stm32h725ae" ]
-stm32h725ag = [ "stm32-metapac/stm32h725ag" ]
-stm32h725ie = [ "stm32-metapac/stm32h725ie" ]
-stm32h725ig = [ "stm32-metapac/stm32h725ig" ]
-stm32h725re = [ "stm32-metapac/stm32h725re" ]
-stm32h725rg = [ "stm32-metapac/stm32h725rg" ]
-stm32h725ve = [ "stm32-metapac/stm32h725ve" ]
-stm32h725vg = [ "stm32-metapac/stm32h725vg" ]
-stm32h725ze = [ "stm32-metapac/stm32h725ze" ]
-stm32h725zg = [ "stm32-metapac/stm32h725zg" ]
-stm32h730ab = [ "stm32-metapac/stm32h730ab" ]
-stm32h730ib = [ "stm32-metapac/stm32h730ib" ]
-stm32h730vb = [ "stm32-metapac/stm32h730vb" ]
-stm32h730zb = [ "stm32-metapac/stm32h730zb" ]
-stm32h733vg = [ "stm32-metapac/stm32h733vg" ]
-stm32h733zg = [ "stm32-metapac/stm32h733zg" ]
-stm32h735ag = [ "stm32-metapac/stm32h735ag" ]
-stm32h735ig = [ "stm32-metapac/stm32h735ig" ]
-stm32h735rg = [ "stm32-metapac/stm32h735rg" ]
-stm32h735vg = [ "stm32-metapac/stm32h735vg" ]
-stm32h735zg = [ "stm32-metapac/stm32h735zg" ]
-stm32h742ag = [ "stm32-metapac/stm32h742ag" ]
-stm32h742ai = [ "stm32-metapac/stm32h742ai" ]
-stm32h742bg = [ "stm32-metapac/stm32h742bg" ]
-stm32h742bi = [ "stm32-metapac/stm32h742bi" ]
-stm32h742ig = [ "stm32-metapac/stm32h742ig" ]
-stm32h742ii = [ "stm32-metapac/stm32h742ii" ]
-stm32h742vg = [ "stm32-metapac/stm32h742vg" ]
-stm32h742vi = [ "stm32-metapac/stm32h742vi" ]
-stm32h742xg = [ "stm32-metapac/stm32h742xg" ]
-stm32h742xi = [ "stm32-metapac/stm32h742xi" ]
-stm32h742zg = [ "stm32-metapac/stm32h742zg" ]
-stm32h742zi = [ "stm32-metapac/stm32h742zi" ]
-stm32h743ag = [ "stm32-metapac/stm32h743ag" ]
-stm32h743ai = [ "stm32-metapac/stm32h743ai" ]
-stm32h743bg = [ "stm32-metapac/stm32h743bg" ]
-stm32h743bi = [ "stm32-metapac/stm32h743bi" ]
-stm32h743ig = [ "stm32-metapac/stm32h743ig" ]
-stm32h743ii = [ "stm32-metapac/stm32h743ii" ]
-stm32h743vg = [ "stm32-metapac/stm32h743vg" ]
-stm32h743vi = [ "stm32-metapac/stm32h743vi" ]
-stm32h743xg = [ "stm32-metapac/stm32h743xg" ]
-stm32h743xi = [ "stm32-metapac/stm32h743xi" ]
-stm32h743zg = [ "stm32-metapac/stm32h743zg" ]
-stm32h743zi = [ "stm32-metapac/stm32h743zi" ]
-stm32h745bg-cm7 = [ "stm32-metapac/stm32h745bg-cm7" ]
-stm32h745bg-cm4 = [ "stm32-metapac/stm32h745bg-cm4" ]
-stm32h745bi-cm7 = [ "stm32-metapac/stm32h745bi-cm7" ]
-stm32h745bi-cm4 = [ "stm32-metapac/stm32h745bi-cm4" ]
-stm32h745ig-cm7 = [ "stm32-metapac/stm32h745ig-cm7" ]
-stm32h745ig-cm4 = [ "stm32-metapac/stm32h745ig-cm4" ]
-stm32h745ii-cm7 = [ "stm32-metapac/stm32h745ii-cm7" ]
-stm32h745ii-cm4 = [ "stm32-metapac/stm32h745ii-cm4" ]
-stm32h745xg-cm7 = [ "stm32-metapac/stm32h745xg-cm7" ]
-stm32h745xg-cm4 = [ "stm32-metapac/stm32h745xg-cm4" ]
-stm32h745xi-cm7 = [ "stm32-metapac/stm32h745xi-cm7" ]
-stm32h745xi-cm4 = [ "stm32-metapac/stm32h745xi-cm4" ]
-stm32h745zg-cm7 = [ "stm32-metapac/stm32h745zg-cm7" ]
-stm32h745zg-cm4 = [ "stm32-metapac/stm32h745zg-cm4" ]
-stm32h745zi-cm7 = [ "stm32-metapac/stm32h745zi-cm7" ]
-stm32h745zi-cm4 = [ "stm32-metapac/stm32h745zi-cm4" ]
-stm32h747ag-cm7 = [ "stm32-metapac/stm32h747ag-cm7" ]
-stm32h747ag-cm4 = [ "stm32-metapac/stm32h747ag-cm4" ]
-stm32h747ai-cm7 = [ "stm32-metapac/stm32h747ai-cm7" ]
-stm32h747ai-cm4 = [ "stm32-metapac/stm32h747ai-cm4" ]
-stm32h747bg-cm7 = [ "stm32-metapac/stm32h747bg-cm7" ]
-stm32h747bg-cm4 = [ "stm32-metapac/stm32h747bg-cm4" ]
-stm32h747bi-cm7 = [ "stm32-metapac/stm32h747bi-cm7" ]
-stm32h747bi-cm4 = [ "stm32-metapac/stm32h747bi-cm4" ]
-stm32h747ig-cm7 = [ "stm32-metapac/stm32h747ig-cm7" ]
-stm32h747ig-cm4 = [ "stm32-metapac/stm32h747ig-cm4" ]
-stm32h747ii-cm7 = [ "stm32-metapac/stm32h747ii-cm7" ]
-stm32h747ii-cm4 = [ "stm32-metapac/stm32h747ii-cm4" ]
-stm32h747xg-cm7 = [ "stm32-metapac/stm32h747xg-cm7" ]
-stm32h747xg-cm4 = [ "stm32-metapac/stm32h747xg-cm4" ]
-stm32h747xi-cm7 = [ "stm32-metapac/stm32h747xi-cm7" ]
-stm32h747xi-cm4 = [ "stm32-metapac/stm32h747xi-cm4" ]
-stm32h747zi-cm7 = [ "stm32-metapac/stm32h747zi-cm7" ]
-stm32h747zi-cm4 = [ "stm32-metapac/stm32h747zi-cm4" ]
-stm32h750ib = [ "stm32-metapac/stm32h750ib" ]
-stm32h750vb = [ "stm32-metapac/stm32h750vb" ]
-stm32h750xb = [ "stm32-metapac/stm32h750xb" ]
-stm32h750zb = [ "stm32-metapac/stm32h750zb" ]
-stm32h753ai = [ "stm32-metapac/stm32h753ai" ]
-stm32h753bi = [ "stm32-metapac/stm32h753bi" ]
-stm32h753ii = [ "stm32-metapac/stm32h753ii" ]
-stm32h753vi = [ "stm32-metapac/stm32h753vi" ]
-stm32h753xi = [ "stm32-metapac/stm32h753xi" ]
-stm32h753zi = [ "stm32-metapac/stm32h753zi" ]
-stm32h755bi-cm7 = [ "stm32-metapac/stm32h755bi-cm7" ]
-stm32h755bi-cm4 = [ "stm32-metapac/stm32h755bi-cm4" ]
-stm32h755ii-cm7 = [ "stm32-metapac/stm32h755ii-cm7" ]
-stm32h755ii-cm4 = [ "stm32-metapac/stm32h755ii-cm4" ]
-stm32h755xi-cm7 = [ "stm32-metapac/stm32h755xi-cm7" ]
-stm32h755xi-cm4 = [ "stm32-metapac/stm32h755xi-cm4" ]
-stm32h755zi-cm7 = [ "stm32-metapac/stm32h755zi-cm7" ]
-stm32h755zi-cm4 = [ "stm32-metapac/stm32h755zi-cm4" ]
-stm32h757ai-cm7 = [ "stm32-metapac/stm32h757ai-cm7" ]
-stm32h757ai-cm4 = [ "stm32-metapac/stm32h757ai-cm4" ]
-stm32h757bi-cm7 = [ "stm32-metapac/stm32h757bi-cm7" ]
-stm32h757bi-cm4 = [ "stm32-metapac/stm32h757bi-cm4" ]
-stm32h757ii-cm7 = [ "stm32-metapac/stm32h757ii-cm7" ]
-stm32h757ii-cm4 = [ "stm32-metapac/stm32h757ii-cm4" ]
-stm32h757xi-cm7 = [ "stm32-metapac/stm32h757xi-cm7" ]
-stm32h757xi-cm4 = [ "stm32-metapac/stm32h757xi-cm4" ]
-stm32h757zi-cm7 = [ "stm32-metapac/stm32h757zi-cm7" ]
-stm32h757zi-cm4 = [ "stm32-metapac/stm32h757zi-cm4" ]
-stm32h7a3ag = [ "stm32-metapac/stm32h7a3ag" ]
-stm32h7a3ai = [ "stm32-metapac/stm32h7a3ai" ]
-stm32h7a3ig = [ "stm32-metapac/stm32h7a3ig" ]
-stm32h7a3ii = [ "stm32-metapac/stm32h7a3ii" ]
-stm32h7a3lg = [ "stm32-metapac/stm32h7a3lg" ]
-stm32h7a3li = [ "stm32-metapac/stm32h7a3li" ]
-stm32h7a3ng = [ "stm32-metapac/stm32h7a3ng" ]
-stm32h7a3ni = [ "stm32-metapac/stm32h7a3ni" ]
-stm32h7a3qi = [ "stm32-metapac/stm32h7a3qi" ]
-stm32h7a3rg = [ "stm32-metapac/stm32h7a3rg" ]
-stm32h7a3ri = [ "stm32-metapac/stm32h7a3ri" ]
-stm32h7a3vg = [ "stm32-metapac/stm32h7a3vg" ]
-stm32h7a3vi = [ "stm32-metapac/stm32h7a3vi" ]
-stm32h7a3zg = [ "stm32-metapac/stm32h7a3zg" ]
-stm32h7a3zi = [ "stm32-metapac/stm32h7a3zi" ]
-stm32h7b0ab = [ "stm32-metapac/stm32h7b0ab" ]
-stm32h7b0ib = [ "stm32-metapac/stm32h7b0ib" ]
-stm32h7b0rb = [ "stm32-metapac/stm32h7b0rb" ]
-stm32h7b0vb = [ "stm32-metapac/stm32h7b0vb" ]
-stm32h7b0zb = [ "stm32-metapac/stm32h7b0zb" ]
-stm32h7b3ai = [ "stm32-metapac/stm32h7b3ai" ]
-stm32h7b3ii = [ "stm32-metapac/stm32h7b3ii" ]
-stm32h7b3li = [ "stm32-metapac/stm32h7b3li" ]
-stm32h7b3ni = [ "stm32-metapac/stm32h7b3ni" ]
-stm32h7b3qi = [ "stm32-metapac/stm32h7b3qi" ]
-stm32h7b3ri = [ "stm32-metapac/stm32h7b3ri" ]
-stm32h7b3vi = [ "stm32-metapac/stm32h7b3vi" ]
-stm32h7b3zi = [ "stm32-metapac/stm32h7b3zi" ]
+stm32g030c6 = [ "stm32-metapac/stm32g030c6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g030c8 = [ "stm32-metapac/stm32g030c8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g030f6 = [ "stm32-metapac/stm32g030f6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g030j6 = [ "stm32-metapac/stm32g030j6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g030k6 = [ "stm32-metapac/stm32g030k6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g030k8 = [ "stm32-metapac/stm32g030k8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g031c4 = [ "stm32-metapac/stm32g031c4", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g031c6 = [ "stm32-metapac/stm32g031c6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g031c8 = [ "stm32-metapac/stm32g031c8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g031f4 = [ "stm32-metapac/stm32g031f4", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g031f6 = [ "stm32-metapac/stm32g031f6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g031f8 = [ "stm32-metapac/stm32g031f8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g031g4 = [ "stm32-metapac/stm32g031g4", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g031g6 = [ "stm32-metapac/stm32g031g6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g031g8 = [ "stm32-metapac/stm32g031g8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g031j4 = [ "stm32-metapac/stm32g031j4", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g031j6 = [ "stm32-metapac/stm32g031j6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g031k4 = [ "stm32-metapac/stm32g031k4", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g031k6 = [ "stm32-metapac/stm32g031k6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g031k8 = [ "stm32-metapac/stm32g031k8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g031y8 = [ "stm32-metapac/stm32g031y8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g041c6 = [ "stm32-metapac/stm32g041c6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g041c8 = [ "stm32-metapac/stm32g041c8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g041f6 = [ "stm32-metapac/stm32g041f6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g041f8 = [ "stm32-metapac/stm32g041f8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g041g6 = [ "stm32-metapac/stm32g041g6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g041g8 = [ "stm32-metapac/stm32g041g8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g041j6 = [ "stm32-metapac/stm32g041j6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g041k6 = [ "stm32-metapac/stm32g041k6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g041k8 = [ "stm32-metapac/stm32g041k8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g041y8 = [ "stm32-metapac/stm32g041y8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g050c6 = [ "stm32-metapac/stm32g050c6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g050c8 = [ "stm32-metapac/stm32g050c8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g050f6 = [ "stm32-metapac/stm32g050f6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g050k6 = [ "stm32-metapac/stm32g050k6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g050k8 = [ "stm32-metapac/stm32g050k8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g051c6 = [ "stm32-metapac/stm32g051c6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g051c8 = [ "stm32-metapac/stm32g051c8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g051f6 = [ "stm32-metapac/stm32g051f6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g051f8 = [ "stm32-metapac/stm32g051f8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g051g6 = [ "stm32-metapac/stm32g051g6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g051g8 = [ "stm32-metapac/stm32g051g8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g051k6 = [ "stm32-metapac/stm32g051k6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g051k8 = [ "stm32-metapac/stm32g051k8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g061c6 = [ "stm32-metapac/stm32g061c6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g061c8 = [ "stm32-metapac/stm32g061c8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g061f6 = [ "stm32-metapac/stm32g061f6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g061f8 = [ "stm32-metapac/stm32g061f8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g061g6 = [ "stm32-metapac/stm32g061g6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g061g8 = [ "stm32-metapac/stm32g061g8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g061k6 = [ "stm32-metapac/stm32g061k6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g061k8 = [ "stm32-metapac/stm32g061k8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g070cb = [ "stm32-metapac/stm32g070cb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g070kb = [ "stm32-metapac/stm32g070kb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g070rb = [ "stm32-metapac/stm32g070rb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g071c6 = [ "stm32-metapac/stm32g071c6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g071c8 = [ "stm32-metapac/stm32g071c8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g071cb = [ "stm32-metapac/stm32g071cb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g071eb = [ "stm32-metapac/stm32g071eb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g071g6 = [ "stm32-metapac/stm32g071g6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g071g8 = [ "stm32-metapac/stm32g071g8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g071gb = [ "stm32-metapac/stm32g071gb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g071k6 = [ "stm32-metapac/stm32g071k6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g071k8 = [ "stm32-metapac/stm32g071k8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g071kb = [ "stm32-metapac/stm32g071kb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g071r6 = [ "stm32-metapac/stm32g071r6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g071r8 = [ "stm32-metapac/stm32g071r8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g071rb = [ "stm32-metapac/stm32g071rb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g081cb = [ "stm32-metapac/stm32g081cb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g081eb = [ "stm32-metapac/stm32g081eb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g081gb = [ "stm32-metapac/stm32g081gb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g081kb = [ "stm32-metapac/stm32g081kb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g081rb = [ "stm32-metapac/stm32g081rb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b0ce = [ "stm32-metapac/stm32g0b0ce", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b0ke = [ "stm32-metapac/stm32g0b0ke", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b0re = [ "stm32-metapac/stm32g0b0re", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b0ve = [ "stm32-metapac/stm32g0b0ve", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1cb = [ "stm32-metapac/stm32g0b1cb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1cc = [ "stm32-metapac/stm32g0b1cc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1ce = [ "stm32-metapac/stm32g0b1ce", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1kb = [ "stm32-metapac/stm32g0b1kb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1kc = [ "stm32-metapac/stm32g0b1kc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1ke = [ "stm32-metapac/stm32g0b1ke", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1mb = [ "stm32-metapac/stm32g0b1mb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1mc = [ "stm32-metapac/stm32g0b1mc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1me = [ "stm32-metapac/stm32g0b1me", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1ne = [ "stm32-metapac/stm32g0b1ne", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1rb = [ "stm32-metapac/stm32g0b1rb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1rc = [ "stm32-metapac/stm32g0b1rc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1re = [ "stm32-metapac/stm32g0b1re", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1vb = [ "stm32-metapac/stm32g0b1vb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1vc = [ "stm32-metapac/stm32g0b1vc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0b1ve = [ "stm32-metapac/stm32g0b1ve", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0c1cc = [ "stm32-metapac/stm32g0c1cc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0c1ce = [ "stm32-metapac/stm32g0c1ce", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0c1kc = [ "stm32-metapac/stm32g0c1kc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0c1ke = [ "stm32-metapac/stm32g0c1ke", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0c1mc = [ "stm32-metapac/stm32g0c1mc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0c1me = [ "stm32-metapac/stm32g0c1me", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0c1ne = [ "stm32-metapac/stm32g0c1ne", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0c1rc = [ "stm32-metapac/stm32g0c1rc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0c1re = [ "stm32-metapac/stm32g0c1re", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0c1vc = [ "stm32-metapac/stm32g0c1vc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g0c1ve = [ "stm32-metapac/stm32g0c1ve", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g431c6 = [ "stm32-metapac/stm32g431c6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g431c8 = [ "stm32-metapac/stm32g431c8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g431cb = [ "stm32-metapac/stm32g431cb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g431k6 = [ "stm32-metapac/stm32g431k6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g431k8 = [ "stm32-metapac/stm32g431k8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g431kb = [ "stm32-metapac/stm32g431kb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g431m6 = [ "stm32-metapac/stm32g431m6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g431m8 = [ "stm32-metapac/stm32g431m8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g431mb = [ "stm32-metapac/stm32g431mb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g431r6 = [ "stm32-metapac/stm32g431r6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g431r8 = [ "stm32-metapac/stm32g431r8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g431rb = [ "stm32-metapac/stm32g431rb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g431v6 = [ "stm32-metapac/stm32g431v6", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g431v8 = [ "stm32-metapac/stm32g431v8", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g431vb = [ "stm32-metapac/stm32g431vb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g441cb = [ "stm32-metapac/stm32g441cb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g441kb = [ "stm32-metapac/stm32g441kb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g441mb = [ "stm32-metapac/stm32g441mb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g441rb = [ "stm32-metapac/stm32g441rb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g441vb = [ "stm32-metapac/stm32g441vb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g471cc = [ "stm32-metapac/stm32g471cc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g471ce = [ "stm32-metapac/stm32g471ce", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g471mc = [ "stm32-metapac/stm32g471mc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g471me = [ "stm32-metapac/stm32g471me", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g471qc = [ "stm32-metapac/stm32g471qc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g471qe = [ "stm32-metapac/stm32g471qe", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g471rc = [ "stm32-metapac/stm32g471rc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g471re = [ "stm32-metapac/stm32g471re", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g471vc = [ "stm32-metapac/stm32g471vc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g471ve = [ "stm32-metapac/stm32g471ve", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473cb = [ "stm32-metapac/stm32g473cb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473cc = [ "stm32-metapac/stm32g473cc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473ce = [ "stm32-metapac/stm32g473ce", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473mb = [ "stm32-metapac/stm32g473mb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473mc = [ "stm32-metapac/stm32g473mc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473me = [ "stm32-metapac/stm32g473me", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473pb = [ "stm32-metapac/stm32g473pb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473pc = [ "stm32-metapac/stm32g473pc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473pe = [ "stm32-metapac/stm32g473pe", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473qb = [ "stm32-metapac/stm32g473qb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473qc = [ "stm32-metapac/stm32g473qc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473qe = [ "stm32-metapac/stm32g473qe", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473rb = [ "stm32-metapac/stm32g473rb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473rc = [ "stm32-metapac/stm32g473rc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473re = [ "stm32-metapac/stm32g473re", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473vb = [ "stm32-metapac/stm32g473vb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473vc = [ "stm32-metapac/stm32g473vc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g473ve = [ "stm32-metapac/stm32g473ve", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474cb = [ "stm32-metapac/stm32g474cb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474cc = [ "stm32-metapac/stm32g474cc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474ce = [ "stm32-metapac/stm32g474ce", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474mb = [ "stm32-metapac/stm32g474mb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474mc = [ "stm32-metapac/stm32g474mc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474me = [ "stm32-metapac/stm32g474me", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474pb = [ "stm32-metapac/stm32g474pb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474pc = [ "stm32-metapac/stm32g474pc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474pe = [ "stm32-metapac/stm32g474pe", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474qb = [ "stm32-metapac/stm32g474qb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474qc = [ "stm32-metapac/stm32g474qc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474qe = [ "stm32-metapac/stm32g474qe", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474rb = [ "stm32-metapac/stm32g474rb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474rc = [ "stm32-metapac/stm32g474rc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474re = [ "stm32-metapac/stm32g474re", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474vb = [ "stm32-metapac/stm32g474vb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474vc = [ "stm32-metapac/stm32g474vc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g474ve = [ "stm32-metapac/stm32g474ve", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g483ce = [ "stm32-metapac/stm32g483ce", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g483me = [ "stm32-metapac/stm32g483me", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g483pe = [ "stm32-metapac/stm32g483pe", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g483qe = [ "stm32-metapac/stm32g483qe", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g483re = [ "stm32-metapac/stm32g483re", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g483ve = [ "stm32-metapac/stm32g483ve", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g484ce = [ "stm32-metapac/stm32g484ce", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g484me = [ "stm32-metapac/stm32g484me", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g484pe = [ "stm32-metapac/stm32g484pe", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g484qe = [ "stm32-metapac/stm32g484qe", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g484re = [ "stm32-metapac/stm32g484re", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g484ve = [ "stm32-metapac/stm32g484ve", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g491cc = [ "stm32-metapac/stm32g491cc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g491ce = [ "stm32-metapac/stm32g491ce", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g491kc = [ "stm32-metapac/stm32g491kc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g491ke = [ "stm32-metapac/stm32g491ke", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g491mc = [ "stm32-metapac/stm32g491mc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g491me = [ "stm32-metapac/stm32g491me", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g491rc = [ "stm32-metapac/stm32g491rc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g491re = [ "stm32-metapac/stm32g491re", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g491vc = [ "stm32-metapac/stm32g491vc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g491ve = [ "stm32-metapac/stm32g491ve", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g4a1ce = [ "stm32-metapac/stm32g4a1ce", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g4a1ke = [ "stm32-metapac/stm32g4a1ke", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g4a1me = [ "stm32-metapac/stm32g4a1me", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g4a1re = [ "stm32-metapac/stm32g4a1re", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32g4a1ve = [ "stm32-metapac/stm32g4a1ve", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h503cb = [ "stm32-metapac/stm32h503cb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h503eb = [ "stm32-metapac/stm32h503eb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h503kb = [ "stm32-metapac/stm32h503kb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h503rb = [ "stm32-metapac/stm32h503rb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h562ag = [ "stm32-metapac/stm32h562ag", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h562ai = [ "stm32-metapac/stm32h562ai", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h562ig = [ "stm32-metapac/stm32h562ig", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h562ii = [ "stm32-metapac/stm32h562ii", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h562rg = [ "stm32-metapac/stm32h562rg", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h562ri = [ "stm32-metapac/stm32h562ri", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h562vg = [ "stm32-metapac/stm32h562vg", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h562vi = [ "stm32-metapac/stm32h562vi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h562zg = [ "stm32-metapac/stm32h562zg", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h562zi = [ "stm32-metapac/stm32h562zi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h563ag = [ "stm32-metapac/stm32h563ag", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h563ai = [ "stm32-metapac/stm32h563ai", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h563ig = [ "stm32-metapac/stm32h563ig", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h563ii = [ "stm32-metapac/stm32h563ii", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h563mi = [ "stm32-metapac/stm32h563mi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h563rg = [ "stm32-metapac/stm32h563rg", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h563ri = [ "stm32-metapac/stm32h563ri", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h563vg = [ "stm32-metapac/stm32h563vg", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h563vi = [ "stm32-metapac/stm32h563vi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h563zg = [ "stm32-metapac/stm32h563zg", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h563zi = [ "stm32-metapac/stm32h563zi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h573ai = [ "stm32-metapac/stm32h573ai", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h573ii = [ "stm32-metapac/stm32h573ii", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h573mi = [ "stm32-metapac/stm32h573mi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h573ri = [ "stm32-metapac/stm32h573ri", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h573vi = [ "stm32-metapac/stm32h573vi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h573zi = [ "stm32-metapac/stm32h573zi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32h723ve = [ "stm32-metapac/stm32h723ve", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h723vg = [ "stm32-metapac/stm32h723vg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h723ze = [ "stm32-metapac/stm32h723ze", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h723zg = [ "stm32-metapac/stm32h723zg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h725ae = [ "stm32-metapac/stm32h725ae", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h725ag = [ "stm32-metapac/stm32h725ag", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h725ie = [ "stm32-metapac/stm32h725ie", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h725ig = [ "stm32-metapac/stm32h725ig", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h725re = [ "stm32-metapac/stm32h725re", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h725rg = [ "stm32-metapac/stm32h725rg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h725ve = [ "stm32-metapac/stm32h725ve", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h725vg = [ "stm32-metapac/stm32h725vg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h725ze = [ "stm32-metapac/stm32h725ze", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h725zg = [ "stm32-metapac/stm32h725zg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h730ab = [ "stm32-metapac/stm32h730ab", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h730ib = [ "stm32-metapac/stm32h730ib", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h730vb = [ "stm32-metapac/stm32h730vb", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h730zb = [ "stm32-metapac/stm32h730zb", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h733vg = [ "stm32-metapac/stm32h733vg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h733zg = [ "stm32-metapac/stm32h733zg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h735ag = [ "stm32-metapac/stm32h735ag", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h735ig = [ "stm32-metapac/stm32h735ig", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h735rg = [ "stm32-metapac/stm32h735rg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h735vg = [ "stm32-metapac/stm32h735vg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h735zg = [ "stm32-metapac/stm32h735zg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h742ag = [ "stm32-metapac/stm32h742ag", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h742ai = [ "stm32-metapac/stm32h742ai", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h742bg = [ "stm32-metapac/stm32h742bg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h742bi = [ "stm32-metapac/stm32h742bi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h742ig = [ "stm32-metapac/stm32h742ig", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h742ii = [ "stm32-metapac/stm32h742ii", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h742vg = [ "stm32-metapac/stm32h742vg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h742vi = [ "stm32-metapac/stm32h742vi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h742xg = [ "stm32-metapac/stm32h742xg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h742xi = [ "stm32-metapac/stm32h742xi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h742zg = [ "stm32-metapac/stm32h742zg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h742zi = [ "stm32-metapac/stm32h742zi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h743ag = [ "stm32-metapac/stm32h743ag", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h743ai = [ "stm32-metapac/stm32h743ai", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h743bg = [ "stm32-metapac/stm32h743bg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h743bi = [ "stm32-metapac/stm32h743bi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h743ig = [ "stm32-metapac/stm32h743ig", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h743ii = [ "stm32-metapac/stm32h743ii", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h743vg = [ "stm32-metapac/stm32h743vg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h743vi = [ "stm32-metapac/stm32h743vi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h743xg = [ "stm32-metapac/stm32h743xg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h743xi = [ "stm32-metapac/stm32h743xi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h743zg = [ "stm32-metapac/stm32h743zg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h743zi = [ "stm32-metapac/stm32h743zi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745bg-cm7 = [ "stm32-metapac/stm32h745bg-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745bg-cm4 = [ "stm32-metapac/stm32h745bg-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745bi-cm7 = [ "stm32-metapac/stm32h745bi-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745bi-cm4 = [ "stm32-metapac/stm32h745bi-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745ig-cm7 = [ "stm32-metapac/stm32h745ig-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745ig-cm4 = [ "stm32-metapac/stm32h745ig-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745ii-cm7 = [ "stm32-metapac/stm32h745ii-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745ii-cm4 = [ "stm32-metapac/stm32h745ii-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745xg-cm7 = [ "stm32-metapac/stm32h745xg-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745xg-cm4 = [ "stm32-metapac/stm32h745xg-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745xi-cm7 = [ "stm32-metapac/stm32h745xi-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745xi-cm4 = [ "stm32-metapac/stm32h745xi-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745zg-cm7 = [ "stm32-metapac/stm32h745zg-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745zg-cm4 = [ "stm32-metapac/stm32h745zg-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745zi-cm7 = [ "stm32-metapac/stm32h745zi-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h745zi-cm4 = [ "stm32-metapac/stm32h745zi-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747ag-cm7 = [ "stm32-metapac/stm32h747ag-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747ag-cm4 = [ "stm32-metapac/stm32h747ag-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747ai-cm7 = [ "stm32-metapac/stm32h747ai-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747ai-cm4 = [ "stm32-metapac/stm32h747ai-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747bg-cm7 = [ "stm32-metapac/stm32h747bg-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747bg-cm4 = [ "stm32-metapac/stm32h747bg-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747bi-cm7 = [ "stm32-metapac/stm32h747bi-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747bi-cm4 = [ "stm32-metapac/stm32h747bi-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747ig-cm7 = [ "stm32-metapac/stm32h747ig-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747ig-cm4 = [ "stm32-metapac/stm32h747ig-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747ii-cm7 = [ "stm32-metapac/stm32h747ii-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747ii-cm4 = [ "stm32-metapac/stm32h747ii-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747xg-cm7 = [ "stm32-metapac/stm32h747xg-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747xg-cm4 = [ "stm32-metapac/stm32h747xg-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747xi-cm7 = [ "stm32-metapac/stm32h747xi-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747xi-cm4 = [ "stm32-metapac/stm32h747xi-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747zi-cm7 = [ "stm32-metapac/stm32h747zi-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h747zi-cm4 = [ "stm32-metapac/stm32h747zi-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h750ib = [ "stm32-metapac/stm32h750ib", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h750vb = [ "stm32-metapac/stm32h750vb", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h750xb = [ "stm32-metapac/stm32h750xb", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h750zb = [ "stm32-metapac/stm32h750zb", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h753ai = [ "stm32-metapac/stm32h753ai", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h753bi = [ "stm32-metapac/stm32h753bi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h753ii = [ "stm32-metapac/stm32h753ii", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h753vi = [ "stm32-metapac/stm32h753vi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h753xi = [ "stm32-metapac/stm32h753xi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h753zi = [ "stm32-metapac/stm32h753zi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h755bi-cm7 = [ "stm32-metapac/stm32h755bi-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h755bi-cm4 = [ "stm32-metapac/stm32h755bi-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h755ii-cm7 = [ "stm32-metapac/stm32h755ii-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h755ii-cm4 = [ "stm32-metapac/stm32h755ii-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h755xi-cm7 = [ "stm32-metapac/stm32h755xi-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h755xi-cm4 = [ "stm32-metapac/stm32h755xi-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h755zi-cm7 = [ "stm32-metapac/stm32h755zi-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h755zi-cm4 = [ "stm32-metapac/stm32h755zi-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h757ai-cm7 = [ "stm32-metapac/stm32h757ai-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h757ai-cm4 = [ "stm32-metapac/stm32h757ai-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h757bi-cm7 = [ "stm32-metapac/stm32h757bi-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h757bi-cm4 = [ "stm32-metapac/stm32h757bi-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h757ii-cm7 = [ "stm32-metapac/stm32h757ii-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h757ii-cm4 = [ "stm32-metapac/stm32h757ii-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h757xi-cm7 = [ "stm32-metapac/stm32h757xi-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h757xi-cm4 = [ "stm32-metapac/stm32h757xi-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h757zi-cm7 = [ "stm32-metapac/stm32h757zi-cm7", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h757zi-cm4 = [ "stm32-metapac/stm32h757zi-cm4", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7a3ag = [ "stm32-metapac/stm32h7a3ag", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7a3ai = [ "stm32-metapac/stm32h7a3ai", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7a3ig = [ "stm32-metapac/stm32h7a3ig", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7a3ii = [ "stm32-metapac/stm32h7a3ii", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7a3lg = [ "stm32-metapac/stm32h7a3lg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7a3li = [ "stm32-metapac/stm32h7a3li", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7a3ng = [ "stm32-metapac/stm32h7a3ng", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7a3ni = [ "stm32-metapac/stm32h7a3ni", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7a3qi = [ "stm32-metapac/stm32h7a3qi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7a3rg = [ "stm32-metapac/stm32h7a3rg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7a3ri = [ "stm32-metapac/stm32h7a3ri", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7a3vg = [ "stm32-metapac/stm32h7a3vg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7a3vi = [ "stm32-metapac/stm32h7a3vi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7a3zg = [ "stm32-metapac/stm32h7a3zg", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7a3zi = [ "stm32-metapac/stm32h7a3zi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7b0ab = [ "stm32-metapac/stm32h7b0ab", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7b0ib = [ "stm32-metapac/stm32h7b0ib", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7b0rb = [ "stm32-metapac/stm32h7b0rb", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7b0vb = [ "stm32-metapac/stm32h7b0vb", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7b0zb = [ "stm32-metapac/stm32h7b0zb", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7b3ai = [ "stm32-metapac/stm32h7b3ai", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7b3ii = [ "stm32-metapac/stm32h7b3ii", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7b3li = [ "stm32-metapac/stm32h7b3li", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7b3ni = [ "stm32-metapac/stm32h7b3ni", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7b3qi = [ "stm32-metapac/stm32h7b3qi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7b3ri = [ "stm32-metapac/stm32h7b3ri", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7b3vi = [ "stm32-metapac/stm32h7b3vi", "dep:fdcan", "fdcan/fdcan_h7" ]
+stm32h7b3zi = [ "stm32-metapac/stm32h7b3zi", "dep:fdcan", "fdcan/fdcan_h7" ]
 stm32l010c6 = [ "stm32-metapac/stm32l010c6" ]
 stm32l010f4 = [ "stm32-metapac/stm32l010f4" ]
 stm32l010k4 = [ "stm32-metapac/stm32l010k4" ]
@@ -1386,86 +1388,86 @@ stm32l4s7zi = [ "stm32-metapac/stm32l4s7zi" ]
 stm32l4s9ai = [ "stm32-metapac/stm32l4s9ai" ]
 stm32l4s9vi = [ "stm32-metapac/stm32l4s9vi" ]
 stm32l4s9zi = [ "stm32-metapac/stm32l4s9zi" ]
-stm32l552cc = [ "stm32-metapac/stm32l552cc" ]
-stm32l552ce = [ "stm32-metapac/stm32l552ce" ]
-stm32l552me = [ "stm32-metapac/stm32l552me" ]
-stm32l552qc = [ "stm32-metapac/stm32l552qc" ]
-stm32l552qe = [ "stm32-metapac/stm32l552qe" ]
-stm32l552rc = [ "stm32-metapac/stm32l552rc" ]
-stm32l552re = [ "stm32-metapac/stm32l552re" ]
-stm32l552vc = [ "stm32-metapac/stm32l552vc" ]
-stm32l552ve = [ "stm32-metapac/stm32l552ve" ]
-stm32l552zc = [ "stm32-metapac/stm32l552zc" ]
-stm32l552ze = [ "stm32-metapac/stm32l552ze" ]
-stm32l562ce = [ "stm32-metapac/stm32l562ce" ]
-stm32l562me = [ "stm32-metapac/stm32l562me" ]
-stm32l562qe = [ "stm32-metapac/stm32l562qe" ]
-stm32l562re = [ "stm32-metapac/stm32l562re" ]
-stm32l562ve = [ "stm32-metapac/stm32l562ve" ]
-stm32l562ze = [ "stm32-metapac/stm32l562ze" ]
-stm32u535cb = [ "stm32-metapac/stm32u535cb" ]
-stm32u535cc = [ "stm32-metapac/stm32u535cc" ]
-stm32u535ce = [ "stm32-metapac/stm32u535ce" ]
-stm32u535je = [ "stm32-metapac/stm32u535je" ]
-stm32u535nc = [ "stm32-metapac/stm32u535nc" ]
-stm32u535ne = [ "stm32-metapac/stm32u535ne" ]
-stm32u535rb = [ "stm32-metapac/stm32u535rb" ]
-stm32u535rc = [ "stm32-metapac/stm32u535rc" ]
-stm32u535re = [ "stm32-metapac/stm32u535re" ]
-stm32u535vc = [ "stm32-metapac/stm32u535vc" ]
-stm32u535ve = [ "stm32-metapac/stm32u535ve" ]
-stm32u545ce = [ "stm32-metapac/stm32u545ce" ]
-stm32u545je = [ "stm32-metapac/stm32u545je" ]
-stm32u545ne = [ "stm32-metapac/stm32u545ne" ]
-stm32u545re = [ "stm32-metapac/stm32u545re" ]
-stm32u545ve = [ "stm32-metapac/stm32u545ve" ]
-stm32u575ag = [ "stm32-metapac/stm32u575ag" ]
-stm32u575ai = [ "stm32-metapac/stm32u575ai" ]
-stm32u575cg = [ "stm32-metapac/stm32u575cg" ]
-stm32u575ci = [ "stm32-metapac/stm32u575ci" ]
-stm32u575og = [ "stm32-metapac/stm32u575og" ]
-stm32u575oi = [ "stm32-metapac/stm32u575oi" ]
-stm32u575qg = [ "stm32-metapac/stm32u575qg" ]
-stm32u575qi = [ "stm32-metapac/stm32u575qi" ]
-stm32u575rg = [ "stm32-metapac/stm32u575rg" ]
-stm32u575ri = [ "stm32-metapac/stm32u575ri" ]
-stm32u575vg = [ "stm32-metapac/stm32u575vg" ]
-stm32u575vi = [ "stm32-metapac/stm32u575vi" ]
-stm32u575zg = [ "stm32-metapac/stm32u575zg" ]
-stm32u575zi = [ "stm32-metapac/stm32u575zi" ]
-stm32u585ai = [ "stm32-metapac/stm32u585ai" ]
-stm32u585ci = [ "stm32-metapac/stm32u585ci" ]
-stm32u585oi = [ "stm32-metapac/stm32u585oi" ]
-stm32u585qi = [ "stm32-metapac/stm32u585qi" ]
-stm32u585ri = [ "stm32-metapac/stm32u585ri" ]
-stm32u585vi = [ "stm32-metapac/stm32u585vi" ]
-stm32u585zi = [ "stm32-metapac/stm32u585zi" ]
-stm32u595ai = [ "stm32-metapac/stm32u595ai" ]
-stm32u595aj = [ "stm32-metapac/stm32u595aj" ]
-stm32u595qi = [ "stm32-metapac/stm32u595qi" ]
-stm32u595qj = [ "stm32-metapac/stm32u595qj" ]
-stm32u595ri = [ "stm32-metapac/stm32u595ri" ]
-stm32u595rj = [ "stm32-metapac/stm32u595rj" ]
-stm32u595vi = [ "stm32-metapac/stm32u595vi" ]
-stm32u595vj = [ "stm32-metapac/stm32u595vj" ]
-stm32u595zi = [ "stm32-metapac/stm32u595zi" ]
-stm32u595zj = [ "stm32-metapac/stm32u595zj" ]
-stm32u599bj = [ "stm32-metapac/stm32u599bj" ]
-stm32u599ni = [ "stm32-metapac/stm32u599ni" ]
-stm32u599nj = [ "stm32-metapac/stm32u599nj" ]
-stm32u599vi = [ "stm32-metapac/stm32u599vi" ]
-stm32u599vj = [ "stm32-metapac/stm32u599vj" ]
-stm32u599zi = [ "stm32-metapac/stm32u599zi" ]
-stm32u599zj = [ "stm32-metapac/stm32u599zj" ]
-stm32u5a5aj = [ "stm32-metapac/stm32u5a5aj" ]
-stm32u5a5qj = [ "stm32-metapac/stm32u5a5qj" ]
-stm32u5a5rj = [ "stm32-metapac/stm32u5a5rj" ]
-stm32u5a5vj = [ "stm32-metapac/stm32u5a5vj" ]
-stm32u5a5zj = [ "stm32-metapac/stm32u5a5zj" ]
-stm32u5a9bj = [ "stm32-metapac/stm32u5a9bj" ]
-stm32u5a9nj = [ "stm32-metapac/stm32u5a9nj" ]
-stm32u5a9vj = [ "stm32-metapac/stm32u5a9vj" ]
-stm32u5a9zj = [ "stm32-metapac/stm32u5a9zj" ]
+stm32l552cc = [ "stm32-metapac/stm32l552cc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l552ce = [ "stm32-metapac/stm32l552ce", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l552me = [ "stm32-metapac/stm32l552me", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l552qc = [ "stm32-metapac/stm32l552qc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l552qe = [ "stm32-metapac/stm32l552qe", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l552rc = [ "stm32-metapac/stm32l552rc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l552re = [ "stm32-metapac/stm32l552re", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l552vc = [ "stm32-metapac/stm32l552vc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l552ve = [ "stm32-metapac/stm32l552ve", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l552zc = [ "stm32-metapac/stm32l552zc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l552ze = [ "stm32-metapac/stm32l552ze", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l562ce = [ "stm32-metapac/stm32l562ce", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l562me = [ "stm32-metapac/stm32l562me", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l562qe = [ "stm32-metapac/stm32l562qe", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l562re = [ "stm32-metapac/stm32l562re", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l562ve = [ "stm32-metapac/stm32l562ve", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32l562ze = [ "stm32-metapac/stm32l562ze", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u535cb = [ "stm32-metapac/stm32u535cb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u535cc = [ "stm32-metapac/stm32u535cc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u535ce = [ "stm32-metapac/stm32u535ce", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u535je = [ "stm32-metapac/stm32u535je", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u535nc = [ "stm32-metapac/stm32u535nc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u535ne = [ "stm32-metapac/stm32u535ne", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u535rb = [ "stm32-metapac/stm32u535rb", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u535rc = [ "stm32-metapac/stm32u535rc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u535re = [ "stm32-metapac/stm32u535re", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u535vc = [ "stm32-metapac/stm32u535vc", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u535ve = [ "stm32-metapac/stm32u535ve", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u545ce = [ "stm32-metapac/stm32u545ce", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u545je = [ "stm32-metapac/stm32u545je", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u545ne = [ "stm32-metapac/stm32u545ne", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u545re = [ "stm32-metapac/stm32u545re", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u545ve = [ "stm32-metapac/stm32u545ve", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u575ag = [ "stm32-metapac/stm32u575ag", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u575ai = [ "stm32-metapac/stm32u575ai", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u575cg = [ "stm32-metapac/stm32u575cg", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u575ci = [ "stm32-metapac/stm32u575ci", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u575og = [ "stm32-metapac/stm32u575og", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u575oi = [ "stm32-metapac/stm32u575oi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u575qg = [ "stm32-metapac/stm32u575qg", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u575qi = [ "stm32-metapac/stm32u575qi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u575rg = [ "stm32-metapac/stm32u575rg", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u575ri = [ "stm32-metapac/stm32u575ri", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u575vg = [ "stm32-metapac/stm32u575vg", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u575vi = [ "stm32-metapac/stm32u575vi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u575zg = [ "stm32-metapac/stm32u575zg", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u575zi = [ "stm32-metapac/stm32u575zi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u585ai = [ "stm32-metapac/stm32u585ai", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u585ci = [ "stm32-metapac/stm32u585ci", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u585oi = [ "stm32-metapac/stm32u585oi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u585qi = [ "stm32-metapac/stm32u585qi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u585ri = [ "stm32-metapac/stm32u585ri", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u585vi = [ "stm32-metapac/stm32u585vi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u585zi = [ "stm32-metapac/stm32u585zi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u595ai = [ "stm32-metapac/stm32u595ai", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u595aj = [ "stm32-metapac/stm32u595aj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u595qi = [ "stm32-metapac/stm32u595qi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u595qj = [ "stm32-metapac/stm32u595qj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u595ri = [ "stm32-metapac/stm32u595ri", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u595rj = [ "stm32-metapac/stm32u595rj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u595vi = [ "stm32-metapac/stm32u595vi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u595vj = [ "stm32-metapac/stm32u595vj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u595zi = [ "stm32-metapac/stm32u595zi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u595zj = [ "stm32-metapac/stm32u595zj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u599bj = [ "stm32-metapac/stm32u599bj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u599ni = [ "stm32-metapac/stm32u599ni", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u599nj = [ "stm32-metapac/stm32u599nj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u599vi = [ "stm32-metapac/stm32u599vi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u599vj = [ "stm32-metapac/stm32u599vj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u599zi = [ "stm32-metapac/stm32u599zi", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u599zj = [ "stm32-metapac/stm32u599zj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u5a5aj = [ "stm32-metapac/stm32u5a5aj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u5a5qj = [ "stm32-metapac/stm32u5a5qj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u5a5rj = [ "stm32-metapac/stm32u5a5rj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u5a5vj = [ "stm32-metapac/stm32u5a5vj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u5a5zj = [ "stm32-metapac/stm32u5a5zj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u5a9bj = [ "stm32-metapac/stm32u5a9bj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u5a9nj = [ "stm32-metapac/stm32u5a9nj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u5a9vj = [ "stm32-metapac/stm32u5a9vj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
+stm32u5a9zj = [ "stm32-metapac/stm32u5a9zj", "dep:fdcan", "fdcan/fdcan_g0_g4_l5" ]
 stm32wb10cc = [ "stm32-metapac/stm32wb10cc" ]
 stm32wb15cc = [ "stm32-metapac/stm32wb15cc" ]
 stm32wb30ce = [ "stm32-metapac/stm32wb30ce" ]
diff --git a/embassy-stm32/build.rs b/embassy-stm32/build.rs
index 1a68dfc9d..35023bf1f 100644
--- a/embassy-stm32/build.rs
+++ b/embassy-stm32/build.rs
@@ -449,9 +449,20 @@ fn main() {
     // ========
     // Generate RccPeripheral impls
 
-    let refcounted_peripherals = HashSet::from(["usart", "adc"]);
+    // count how many times each xxENR field is used, to enable refcounting if used more than once.
+    let mut rcc_field_count: HashMap<_, usize> = HashMap::new();
+    for p in METADATA.peripherals {
+        if let Some(rcc) = &p.rcc {
+            let en = rcc.enable.as_ref().unwrap();
+            *rcc_field_count.entry((en.register, en.field)).or_insert(0) += 1;
+        }
+    }
+
+    let force_refcount = HashSet::from(["usart"]);
     let mut refcount_statics = BTreeSet::new();
 
+    let mut clock_names = BTreeSet::new();
+
     for p in METADATA.peripherals {
         if !singletons.contains(&p.name.to_string()) {
             continue;
@@ -483,11 +494,12 @@ fn main() {
 
             let ptype = if let Some(reg) = &p.registers { reg.kind } else { "" };
             let pname = format_ident!("{}", p.name);
-            let clk = format_ident!("{}", rcc.clock);
             let en_reg = format_ident!("{}", en.register);
             let set_en_field = format_ident!("set_{}", en.field);
 
-            let (before_enable, before_disable) = if refcounted_peripherals.contains(ptype) {
+            let refcount =
+                force_refcount.contains(ptype) || *rcc_field_count.get(&(en.register, en.field)).unwrap() > 1;
+            let (before_enable, before_disable) = if refcount {
                 let refcount_static =
                     format_ident!("{}_{}", en.register.to_ascii_uppercase(), en.field.to_ascii_uppercase());
 
@@ -511,14 +523,7 @@ fn main() {
                 (TokenStream::new(), TokenStream::new())
             };
 
-            let mux_supported = HashSet::from(["c0", "h5", "h50", "h7", "h7ab", "h7rm0433", "g0", "g4", "l4"])
-                .contains(rcc_registers.version);
             let mux_for = |mux: Option<&'static PeripheralRccRegister>| {
-                // restrict mux implementation to supported versions
-                if !mux_supported {
-                    return None;
-                }
-
                 let mux = mux?;
                 let fieldset = rcc_enum_map.get(mux.register)?;
                 let enumm = fieldset.get(mux.field)?;
@@ -539,15 +544,9 @@ fn main() {
                         .map(|v| {
                             let variant_name = format_ident!("{}", v.name);
                             let clock_name = format_ident!("{}", v.name.to_ascii_lowercase());
-
-                            if v.name.starts_with("HCLK") || v.name.starts_with("PCLK") || v.name == "SYS" {
-                                quote! {
-                                    #enum_name::#variant_name => unsafe { crate::rcc::get_freqs().#clock_name },
-                                }
-                            } else {
-                                quote! {
-                                    #enum_name::#variant_name => unsafe { crate::rcc::get_freqs().#clock_name.unwrap() },
-                                }
+                            clock_names.insert(v.name.to_ascii_lowercase());
+                            quote! {
+                                #enum_name::#variant_name => unsafe { crate::rcc::get_freqs().#clock_name.unwrap() },
                             }
                         })
                         .collect();
@@ -558,19 +557,21 @@ fn main() {
                         #[allow(unreachable_patterns)]
                         match crate::pac::RCC.#fieldset_name().read().#field_name() {
                             #match_arms
-
                             _ => unreachable!(),
                         }
                     }
                 }
-                None => quote! {
-                    unsafe { crate::rcc::get_freqs().#clk }
-                },
+                None => {
+                    let clock_name = format_ident!("{}", rcc.clock);
+                    clock_names.insert(rcc.clock.to_string());
+                    quote! {
+                        unsafe { crate::rcc::get_freqs().#clock_name.unwrap() }
+                    }
+                }
             };
 
             /*
                 A refcount leak can result if the same field is shared by peripherals with different stop modes
-
                 This condition should be checked in stm32-data
             */
             let stop_refcount = match rcc.stop_mode {
@@ -617,6 +618,39 @@ fn main() {
         }
     }
 
+    // Generate RCC
+    clock_names.insert("sys".to_string());
+    clock_names.insert("rtc".to_string());
+    let clock_idents: Vec<_> = clock_names.iter().map(|n| format_ident!("{}", n)).collect();
+    g.extend(quote! {
+        #[derive(Clone, Copy, Debug)]
+        #[cfg_attr(feature = "defmt", derive(defmt::Format))]
+        pub struct Clocks {
+            #(
+                pub #clock_idents: Option<crate::time::Hertz>,
+            )*
+        }
+    });
+
+    let clocks_macro = quote!(
+        macro_rules! set_clocks {
+            ($($(#[$m:meta])* $k:ident: $v:expr,)*) => {
+                {
+                    #[allow(unused)]
+                    struct Temp {
+                        $($(#[$m])* $k: Option<crate::time::Hertz>,)*
+                    }
+                    let all = Temp {
+                        $($(#[$m])* $k: $v,)*
+                    };
+                    crate::rcc::set_freqs(crate::rcc::Clocks {
+                        #( #clock_idents: all.#clock_idents, )*
+                    });
+                }
+            };
+        }
+    );
+
     let refcount_mod: TokenStream = refcount_statics
         .iter()
         .map(|refcount_static| {
@@ -735,13 +769,20 @@ fn main() {
         (("can", "TX"), quote!(crate::can::TxPin)),
         (("can", "RX"), quote!(crate::can::RxPin)),
         (("eth", "REF_CLK"), quote!(crate::eth::RefClkPin)),
+        (("eth", "RX_CLK"), quote!(crate::eth::RXClkPin)),
+        (("eth", "TX_CLK"), quote!(crate::eth::TXClkPin)),
         (("eth", "MDIO"), quote!(crate::eth::MDIOPin)),
         (("eth", "MDC"), quote!(crate::eth::MDCPin)),
         (("eth", "CRS_DV"), quote!(crate::eth::CRSPin)),
+        (("eth", "RX_DV"), quote!(crate::eth::RXDVPin)),
         (("eth", "RXD0"), quote!(crate::eth::RXD0Pin)),
         (("eth", "RXD1"), quote!(crate::eth::RXD1Pin)),
+        (("eth", "RXD2"), quote!(crate::eth::RXD2Pin)),
+        (("eth", "RXD3"), quote!(crate::eth::RXD3Pin)),
         (("eth", "TXD0"), quote!(crate::eth::TXD0Pin)),
         (("eth", "TXD1"), quote!(crate::eth::TXD1Pin)),
+        (("eth", "TXD2"), quote!(crate::eth::TXD2Pin)),
+        (("eth", "TXD3"), quote!(crate::eth::TXD3Pin)),
         (("eth", "TX_EN"), quote!(crate::eth::TXEnPin)),
         (("fmc", "A0"), quote!(crate::fmc::A0Pin)),
         (("fmc", "A1"), quote!(crate::fmc::A1Pin)),
@@ -942,9 +983,9 @@ fn main() {
                     } else if pin.signal.starts_with("INN") {
                         // TODO handle in the future when embassy supports differential measurements
                         None
-                    } else if pin.signal.starts_with("IN") && pin.signal.ends_with("b") {
+                    } else if pin.signal.starts_with("IN") && pin.signal.ends_with('b') {
                         // we number STM32L1 ADC bank 1 as 0..=31, bank 2 as 32..=63
-                        let signal = pin.signal.strip_prefix("IN").unwrap().strip_suffix("b").unwrap();
+                        let signal = pin.signal.strip_prefix("IN").unwrap().strip_suffix('b').unwrap();
                         Some(32u8 + signal.parse::<u8>().unwrap())
                     } else if pin.signal.starts_with("IN") {
                         Some(pin.signal.strip_prefix("IN").unwrap().parse().unwrap())
@@ -1016,6 +1057,10 @@ fn main() {
         (("dac", "CH2"), quote!(crate::dac::DacDma2)),
         (("timer", "UP"), quote!(crate::timer::UpDma)),
         (("hash", "IN"), quote!(crate::hash::Dma)),
+        (("timer", "CH1"), quote!(crate::timer::Ch1Dma)),
+        (("timer", "CH2"), quote!(crate::timer::Ch2Dma)),
+        (("timer", "CH3"), quote!(crate::timer::Ch3Dma)),
+        (("timer", "CH4"), quote!(crate::timer::Ch4Dma)),
     ]
     .into();
 
@@ -1031,16 +1076,6 @@ fn main() {
                 }
 
                 if let Some(tr) = signals.get(&(regs.kind, ch.signal)) {
-                    // TIM6 of stm32f334 is special, DMA channel for TIM6 depending on SYSCFG state
-                    if chip_name.starts_with("stm32f334") && p.name == "TIM6" {
-                        continue;
-                    }
-
-                    // TIM6 of stm32f378 is special, DMA channel for TIM6 depending on SYSCFG state
-                    if chip_name.starts_with("stm32f378") && p.name == "TIM6" {
-                        continue;
-                    }
-
                     let peri = format_ident!("{}", p.name);
 
                     let channel = if let Some(channel) = &ch.channel {
@@ -1199,7 +1234,7 @@ fn main() {
         ADC3 and higher are assigned to the adc34 clock in the table
         The adc3_common cfg directive is added if ADC3_COMMON exists
     */
-    let has_adc3 = METADATA.peripherals.iter().find(|p| p.name == "ADC3_COMMON").is_some();
+    let has_adc3 = METADATA.peripherals.iter().any(|p| p.name == "ADC3_COMMON");
     let set_adc345 = HashSet::from(["ADC3", "ADC4", "ADC5"]);
 
     for m in METADATA
@@ -1338,7 +1373,7 @@ fn main() {
         }
     }
 
-    let mut m = String::new();
+    let mut m = clocks_macro.to_string();
 
     // DO NOT ADD more macros like these.
     // These turned to be a bad idea!
@@ -1383,6 +1418,7 @@ fn main() {
 
     // =======
     // ADC3_COMMON is present
+    #[allow(clippy::print_literal)]
     if has_adc3 {
         println!("cargo:rustc-cfg={}", "adc3_common");
     }
diff --git a/embassy-stm32/src/adc/f1.rs b/embassy-stm32/src/adc/f1.rs
index fb27bb87b..c896d8e3a 100644
--- a/embassy-stm32/src/adc/f1.rs
+++ b/embassy-stm32/src/adc/f1.rs
@@ -6,7 +6,6 @@ use embassy_hal_internal::into_ref;
 use embedded_hal_02::blocking::delay::DelayUs;
 
 use crate::adc::{Adc, AdcPin, Instance, SampleTime};
-use crate::rcc::get_freqs;
 use crate::time::Hertz;
 use crate::{interrupt, Peripheral};
 
@@ -80,7 +79,7 @@ impl<'d, T: Instance> Adc<'d, T> {
     }
 
     fn freq() -> Hertz {
-        unsafe { get_freqs() }.adc.unwrap()
+        T::frequency()
     }
 
     pub fn sample_time_for_us(&self, us: u32) -> SampleTime {
diff --git a/embassy-stm32/src/adc/f3.rs b/embassy-stm32/src/adc/f3.rs
index 6f59c230f..6606a2b9c 100644
--- a/embassy-stm32/src/adc/f3.rs
+++ b/embassy-stm32/src/adc/f3.rs
@@ -102,7 +102,7 @@ impl<'d, T: Instance> Adc<'d, T> {
     }
 
     fn freq() -> Hertz {
-        <T as crate::adc::sealed::Instance>::frequency()
+        <T as crate::rcc::sealed::RccPeripheral>::frequency()
     }
 
     pub fn sample_time_for_us(&self, us: u32) -> SampleTime {
diff --git a/embassy-stm32/src/adc/mod.rs b/embassy-stm32/src/adc/mod.rs
index e4dd35c34..d21c3053f 100644
--- a/embassy-stm32/src/adc/mod.rs
+++ b/embassy-stm32/src/adc/mod.rs
@@ -61,8 +61,6 @@ pub(crate) mod sealed {
         fn regs() -> crate::pac::adc::Adc;
         #[cfg(not(any(adc_f1, adc_v1, adc_f3_v2, adc_f3_v1_1, adc_g0)))]
         fn common_regs() -> crate::pac::adccommon::AdcCommon;
-        #[cfg(adc_f3)]
-        fn frequency() -> crate::time::Hertz;
         #[cfg(any(adc_f1, adc_f3, adc_v1, adc_f3_v1_1))]
         fn state() -> &'static State;
     }
@@ -103,11 +101,6 @@ foreach_adc!(
                 return crate::pac::$common_inst
             }
 
-            #[cfg(adc_f3)]
-            fn frequency() -> crate::time::Hertz {
-                unsafe { crate::rcc::get_freqs() }.$clock.unwrap()
-            }
-
             #[cfg(any(adc_f1, adc_f3, adc_v1, adc_f3_v1_1))]
             fn state() -> &'static sealed::State {
                 static STATE: sealed::State = sealed::State::new();
diff --git a/embassy-stm32/src/adc/v2.rs b/embassy-stm32/src/adc/v2.rs
index 4622b40a9..b37ac5a5d 100644
--- a/embassy-stm32/src/adc/v2.rs
+++ b/embassy-stm32/src/adc/v2.rs
@@ -34,7 +34,7 @@ impl AdcPin<ADC1> for Temperature {}
 impl super::sealed::AdcPin<ADC1> for Temperature {
     fn channel(&self) -> u8 {
         cfg_if::cfg_if! {
-            if #[cfg(any(stm32f40, stm32f41))] {
+            if #[cfg(any(stm32f2, stm32f40, stm32f41))] {
                 16
             } else {
                 18
@@ -67,7 +67,11 @@ enum Prescaler {
 
 impl Prescaler {
     fn from_pclk2(freq: Hertz) -> Self {
+        // Datasheet for F2 specifies min frequency 0.6 MHz, and max 30 MHz (with VDDA 2.4-3.6V).
+        #[cfg(stm32f2)]
+        const MAX_FREQUENCY: Hertz = Hertz(30_000_000);
         // Datasheet for both F4 and F7 specifies min frequency 0.6 MHz, typ freq. 30 MHz and max 36 MHz.
+        #[cfg(not(stm32f2))]
         const MAX_FREQUENCY: Hertz = Hertz(36_000_000);
         let raw_div = freq.0 / MAX_FREQUENCY.0;
         match raw_div {
diff --git a/embassy-stm32/src/can/bxcan.rs b/embassy-stm32/src/can/bxcan.rs
index cc87b2565..7e00eca6f 100644
--- a/embassy-stm32/src/can/bxcan.rs
+++ b/embassy-stm32/src/can/bxcan.rs
@@ -13,9 +13,12 @@ use crate::gpio::sealed::AFType;
 use crate::interrupt::typelevel::Interrupt;
 use crate::pac::can::vals::{Ide, Lec};
 use crate::rcc::RccPeripheral;
-use crate::time::Hertz;
 use crate::{interrupt, peripherals, Peripheral};
 
+pub mod enums;
+use enums::*;
+pub mod util;
+
 /// Contains CAN frame and additional metadata.
 ///
 /// Timestamp is available if `time` feature is enabled.
@@ -93,23 +96,6 @@ pub struct Can<'d, T: Instance> {
     can: bxcan::Can<BxcanInstance<'d, T>>,
 }
 
-/// CAN bus error
-#[allow(missing_docs)]
-#[derive(Debug)]
-#[cfg_attr(feature = "defmt", derive(defmt::Format))]
-pub enum BusError {
-    Stuff,
-    Form,
-    Acknowledge,
-    BitRecessive,
-    BitDominant,
-    Crc,
-    Software,
-    BusOff,
-    BusPassive,
-    BusWarning,
-}
-
 /// Error returned by `try_read`
 #[derive(Debug)]
 #[cfg_attr(feature = "defmt", derive(defmt::Format))]
@@ -186,8 +172,15 @@ impl<'d, T: Instance> Can<'d, T> {
 
     /// Set CAN bit rate.
     pub fn set_bitrate(&mut self, bitrate: u32) {
-        let bit_timing = Self::calc_bxcan_timings(T::frequency(), bitrate).unwrap();
-        self.can.modify_config().set_bit_timing(bit_timing).leave_disabled();
+        let bit_timing = util::calc_can_timings(T::frequency(), bitrate).unwrap();
+        let sjw = u8::from(bit_timing.sync_jump_width) as u32;
+        let seg1 = u8::from(bit_timing.seg1) as u32;
+        let seg2 = u8::from(bit_timing.seg2) as u32;
+        let prescaler = u16::from(bit_timing.prescaler) as u32;
+        self.can
+            .modify_config()
+            .set_bit_timing((sjw - 1) << 24 | (seg1 - 1) << 16 | (seg2 - 1) << 20 | (prescaler - 1))
+            .leave_disabled();
     }
 
     /// Enables the peripheral and synchronizes with the bus.
@@ -302,97 +295,6 @@ impl<'d, T: Instance> Can<'d, T> {
         }
     }
 
-    const fn calc_bxcan_timings(periph_clock: Hertz, can_bitrate: u32) -> Option<u32> {
-        const BS1_MAX: u8 = 16;
-        const BS2_MAX: u8 = 8;
-        const MAX_SAMPLE_POINT_PERMILL: u16 = 900;
-
-        let periph_clock = periph_clock.0;
-
-        if can_bitrate < 1000 {
-            return None;
-        }
-
-        // Ref. "Automatic Baudrate Detection in CANopen Networks", U. Koppe, MicroControl GmbH & Co. KG
-        //      CAN in Automation, 2003
-        //
-        // According to the source, optimal quanta per bit are:
-        //   Bitrate        Optimal Maximum
-        //   1000 kbps      8       10
-        //   500  kbps      16      17
-        //   250  kbps      16      17
-        //   125  kbps      16      17
-        let max_quanta_per_bit: u8 = if can_bitrate >= 1_000_000 { 10 } else { 17 };
-
-        // Computing (prescaler * BS):
-        //   BITRATE = 1 / (PRESCALER * (1 / PCLK) * (1 + BS1 + BS2))       -- See the Reference Manual
-        //   BITRATE = PCLK / (PRESCALER * (1 + BS1 + BS2))                 -- Simplified
-        // let:
-        //   BS = 1 + BS1 + BS2                                             -- Number of time quanta per bit
-        //   PRESCALER_BS = PRESCALER * BS
-        // ==>
-        //   PRESCALER_BS = PCLK / BITRATE
-        let prescaler_bs = periph_clock / can_bitrate;
-
-        // Searching for such prescaler value so that the number of quanta per bit is highest.
-        let mut bs1_bs2_sum = max_quanta_per_bit - 1;
-        while (prescaler_bs % (1 + bs1_bs2_sum) as u32) != 0 {
-            if bs1_bs2_sum <= 2 {
-                return None; // No solution
-            }
-            bs1_bs2_sum -= 1;
-        }
-
-        let prescaler = prescaler_bs / (1 + bs1_bs2_sum) as u32;
-        if (prescaler < 1) || (prescaler > 1024) {
-            return None; // No solution
-        }
-
-        // Now we have a constraint: (BS1 + BS2) == bs1_bs2_sum.
-        // We need to find such values so that the sample point is as close as possible to the optimal value,
-        // which is 87.5%, which is 7/8.
-        //
-        //   Solve[(1 + bs1)/(1 + bs1 + bs2) == 7/8, bs2]  (* Where 7/8 is 0.875, the recommended sample point location *)
-        //   {{bs2 -> (1 + bs1)/7}}
-        //
-        // Hence:
-        //   bs2 = (1 + bs1) / 7
-        //   bs1 = (7 * bs1_bs2_sum - 1) / 8
-        //
-        // Sample point location can be computed as follows:
-        //   Sample point location = (1 + bs1) / (1 + bs1 + bs2)
-        //
-        // Since the optimal solution is so close to the maximum, we prepare two solutions, and then pick the best one:
-        //   - With rounding to nearest
-        //   - With rounding to zero
-        let mut bs1 = ((7 * bs1_bs2_sum - 1) + 4) / 8; // Trying rounding to nearest first
-        let mut bs2 = bs1_bs2_sum - bs1;
-        core::assert!(bs1_bs2_sum > bs1);
-
-        let sample_point_permill = 1000 * ((1 + bs1) / (1 + bs1 + bs2)) as u16;
-        if sample_point_permill > MAX_SAMPLE_POINT_PERMILL {
-            // Nope, too far; now rounding to zero
-            bs1 = (7 * bs1_bs2_sum - 1) / 8;
-            bs2 = bs1_bs2_sum - bs1;
-        }
-
-        // Check is BS1 and BS2 are in range
-        if (bs1 < 1) || (bs1 > BS1_MAX) || (bs2 < 1) || (bs2 > BS2_MAX) {
-            return None;
-        }
-
-        // Check if final bitrate matches the requested
-        if can_bitrate != (periph_clock / (prescaler * (1 + bs1 + bs2) as u32)) {
-            return None;
-        }
-
-        // One is recommended by DS-015, CANOpen, and DeviceNet
-        let sjw = 1;
-
-        // Pack into BTR register values
-        Some((sjw - 1) << 24 | (bs1 as u32 - 1) << 16 | (bs2 as u32 - 1) << 20 | (prescaler - 1))
-    }
-
     /// Split the CAN driver into transmit and receive halves.
     ///
     /// Useful for doing separate transmit/receive tasks.
diff --git a/embassy-stm32/src/can/enums.rs b/embassy-stm32/src/can/enums.rs
new file mode 100644
index 000000000..36139a45c
--- /dev/null
+++ b/embassy-stm32/src/can/enums.rs
@@ -0,0 +1,30 @@
+//! Enums shared between CAN controller types.
+
+/// Bus error
+#[derive(Debug)]
+#[cfg_attr(feature = "defmt", derive(defmt::Format))]
+pub enum BusError {
+    /// Bit stuffing error - more than 5 equal bits
+    Stuff,
+    /// Form error - A fixed format part of a received message has wrong format
+    Form,
+    /// The message transmitted by the FDCAN was not acknowledged by another node.
+    Acknowledge,
+    /// Bit0Error: During the transmission of a message the device wanted to send a dominant level
+    /// but the monitored bus value was recessive.
+    BitRecessive,
+    /// Bit1Error: During the transmission of a message the device wanted to send a recessive level
+    /// but the monitored bus value was dominant.
+    BitDominant,
+    /// The CRC check sum of a received message was incorrect. The CRC of an
+    /// incoming message does not match with the CRC calculated from the received data.
+    Crc,
+    /// A software error occured
+    Software,
+    ///  The FDCAN is in Bus_Off state.
+    BusOff,
+    ///  The FDCAN is in the Error_Passive state.
+    BusPassive,
+    ///  At least one of error counter has reached the Error_Warning limit of 96.
+    BusWarning,
+}
diff --git a/embassy-stm32/src/can/fdcan.rs b/embassy-stm32/src/can/fdcan.rs
index 0cc2559cf..faf4af73f 100644
--- a/embassy-stm32/src/can/fdcan.rs
+++ b/embassy-stm32/src/can/fdcan.rs
@@ -1,14 +1,577 @@
-use crate::peripherals;
+use core::future::poll_fn;
+use core::marker::PhantomData;
+use core::ops::{Deref, DerefMut};
+use core::task::Poll;
+
+use cfg_if::cfg_if;
+use embassy_hal_internal::{into_ref, PeripheralRef};
+pub use fdcan::frame::{FrameFormat, RxFrameInfo, TxFrameHeader};
+pub use fdcan::id::{ExtendedId, Id, StandardId};
+use fdcan::message_ram::RegisterBlock;
+use fdcan::{self, LastErrorCode};
+pub use fdcan::{config, filter};
+
+use crate::gpio::sealed::AFType;
+use crate::interrupt::typelevel::Interrupt;
+use crate::rcc::RccPeripheral;
+use crate::{interrupt, peripherals, Peripheral};
+
+pub mod enums;
+use enums::*;
+pub mod util;
+
+/// CAN Frame returned by read
+pub struct RxFrame {
+    /// CAN Header info: frame ID, data length and other meta
+    pub header: RxFrameInfo,
+    /// CAN(0-8 bytes) or FDCAN(0-64 bytes) Frame data
+    pub data: Data,
+    /// Reception time.
+    #[cfg(feature = "time")]
+    pub timestamp: embassy_time::Instant,
+}
+
+/// CAN frame used for write
+pub struct TxFrame {
+    /// CAN Header info: frame ID, data length and other meta
+    pub header: TxFrameHeader,
+    /// CAN(0-8 bytes) or FDCAN(0-64 bytes) Frame data
+    pub data: Data,
+}
+
+impl TxFrame {
+    /// Create new TX frame from header and data
+    pub fn new(header: TxFrameHeader, data: &[u8]) -> Option<Self> {
+        if data.len() < header.len as usize {
+            return None;
+        }
+
+        let Some(data) = Data::new(data) else { return None };
+
+        Some(TxFrame { header, data })
+    }
+
+    fn from_preserved(header: TxFrameHeader, data32: &[u32]) -> Option<Self> {
+        let mut data = [0u8; 64];
+
+        for i in 0..data32.len() {
+            data[4 * i..][..4].copy_from_slice(&data32[i].to_le_bytes());
+        }
+
+        let Some(data) = Data::new(&data) else { return None };
+
+        Some(TxFrame { header, data })
+    }
+
+    /// Access frame data. Slice length will match header.
+    pub fn data(&self) -> &[u8] {
+        &self.data.bytes[..(self.header.len as usize)]
+    }
+}
+
+impl RxFrame {
+    pub(crate) fn new(
+        header: RxFrameInfo,
+        data: &[u8],
+        #[cfg(feature = "time")] timestamp: embassy_time::Instant,
+    ) -> Self {
+        let data = Data::new(&data).unwrap_or_else(|| Data::empty());
+
+        RxFrame {
+            header,
+            data,
+            #[cfg(feature = "time")]
+            timestamp,
+        }
+    }
+
+    /// Access frame data. Slice length will match header.
+    pub fn data(&self) -> &[u8] {
+        &self.data.bytes[..(self.header.len as usize)]
+    }
+}
+
+/// Payload of a (FD)CAN data frame.
+///
+/// Contains 0 to 64 Bytes of data.
+#[derive(Debug, Copy, Clone)]
+pub struct Data {
+    pub(crate) bytes: [u8; 64],
+}
+
+impl Data {
+    /// Creates a data payload from a raw byte slice.
+    ///
+    /// Returns `None` if `data` is more than 64 bytes (which is the maximum) or
+    /// cannot be represented with an FDCAN DLC.
+    pub fn new(data: &[u8]) -> Option<Self> {
+        if !Data::is_valid_len(data.len()) {
+            return None;
+        }
+
+        let mut bytes = [0; 64];
+        bytes[..data.len()].copy_from_slice(data);
+
+        Some(Self { bytes })
+    }
+
+    /// Raw read access to data.
+    pub fn raw(&self) -> &[u8] {
+        &self.bytes
+    }
+
+    /// Checks if the length can be encoded in FDCAN DLC field.
+    pub const fn is_valid_len(len: usize) -> bool {
+        match len {
+            0..=8 => true,
+            12 => true,
+            16 => true,
+            20 => true,
+            24 => true,
+            32 => true,
+            48 => true,
+            64 => true,
+            _ => false,
+        }
+    }
+
+    /// Creates an empty data payload containing 0 bytes.
+    #[inline]
+    pub const fn empty() -> Self {
+        Self { bytes: [0; 64] }
+    }
+}
+
+/// Interrupt handler channel 0.
+pub struct IT0InterruptHandler<T: Instance> {
+    _phantom: PhantomData<T>,
+}
+
+// We use IT0 for everything currently
+impl<T: Instance> interrupt::typelevel::Handler<T::IT0Interrupt> for IT0InterruptHandler<T> {
+    unsafe fn on_interrupt() {
+        let regs = T::regs();
+
+        let ir = regs.ir().read();
+
+        if ir.tc() {
+            regs.ir().write(|w| w.set_tc(true));
+            T::state().tx_waker.wake();
+        }
+
+        if ir.tefn() {
+            regs.ir().write(|w| w.set_tefn(true));
+            T::state().tx_waker.wake();
+        }
+
+        if ir.ped() || ir.pea() {
+            regs.ir().write(|w| {
+                w.set_ped(true);
+                w.set_pea(true);
+            });
+        }
+
+        if ir.rfn(0) {
+            regs.ir().write(|w| w.set_rfn(0, true));
+            T::state().rx_waker.wake();
+        }
+
+        if ir.rfn(1) {
+            regs.ir().write(|w| w.set_rfn(1, true));
+            T::state().rx_waker.wake();
+        }
+    }
+}
+
+/// Interrupt handler channel 1.
+pub struct IT1InterruptHandler<T: Instance> {
+    _phantom: PhantomData<T>,
+}
+
+impl<T: Instance> interrupt::typelevel::Handler<T::IT1Interrupt> for IT1InterruptHandler<T> {
+    unsafe fn on_interrupt() {}
+}
+
+impl BusError {
+    fn try_from(lec: LastErrorCode) -> Option<BusError> {
+        match lec {
+            LastErrorCode::AckError => Some(BusError::Acknowledge),
+            // `0` data bit encodes a dominant state. `1` data bit is recessive.
+            // Bit0Error: During transmit, the node wanted to send a 0 but monitored a 1
+            LastErrorCode::Bit0Error => Some(BusError::BitRecessive),
+            LastErrorCode::Bit1Error => Some(BusError::BitDominant),
+            LastErrorCode::CRCError => Some(BusError::Crc),
+            LastErrorCode::FormError => Some(BusError::Form),
+            LastErrorCode::StuffError => Some(BusError::Stuff),
+            _ => None,
+        }
+    }
+}
+
+/// Operating modes trait
+pub trait FdcanOperatingMode {}
+impl FdcanOperatingMode for fdcan::PoweredDownMode {}
+impl FdcanOperatingMode for fdcan::ConfigMode {}
+impl FdcanOperatingMode for fdcan::InternalLoopbackMode {}
+impl FdcanOperatingMode for fdcan::ExternalLoopbackMode {}
+impl FdcanOperatingMode for fdcan::NormalOperationMode {}
+impl FdcanOperatingMode for fdcan::RestrictedOperationMode {}
+impl FdcanOperatingMode for fdcan::BusMonitoringMode {}
+impl FdcanOperatingMode for fdcan::TestMode {}
+
+/// FDCAN Instance
+pub struct Fdcan<'d, T: Instance, M: FdcanOperatingMode> {
+    /// Reference to internals.
+    pub can: fdcan::FdCan<FdcanInstance<'d, T>, M>,
+    ns_per_timer_tick: u64, // For FDCAN internal timer
+}
+
+fn calc_ns_per_timer_tick<T: Instance>(mode: config::FrameTransmissionConfig) -> u64 {
+    match mode {
+        // Use timestamp from Rx FIFO to adjust timestamp reported to user
+        config::FrameTransmissionConfig::ClassicCanOnly => {
+            let freq = T::frequency();
+            let prescale: u64 =
+                ({ T::regs().nbtp().read().nbrp() } + 1) as u64 * ({ T::regs().tscc().read().tcp() } + 1) as u64;
+            1_000_000_000 as u64 / (freq.0 as u64 * prescale)
+        }
+        // For VBR this is too hard because the FDCAN timer switches clock rate you need to configure to use
+        // timer3 instead which is too hard to do from this module.
+        _ => 0,
+    }
+}
+
+#[cfg(feature = "time")]
+fn calc_timestamp<T: Instance>(ns_per_timer_tick: u64, ts_val: u16) -> embassy_time::Instant {
+    let now_embassy = embassy_time::Instant::now();
+    if ns_per_timer_tick == 0 {
+        return now_embassy;
+    }
+    let now_can = { T::regs().tscv().read().tsc() };
+    let delta = now_can.overflowing_sub(ts_val).0 as u64;
+    let ns = ns_per_timer_tick * delta as u64;
+    now_embassy - embassy_time::Duration::from_nanos(ns)
+}
+
+fn curr_error<T: Instance>() -> Option<BusError> {
+    let err = { T::regs().psr().read() };
+    if err.bo() {
+        return Some(BusError::BusOff);
+    } else if err.ep() {
+        return Some(BusError::BusPassive);
+    } else if err.ew() {
+        return Some(BusError::BusWarning);
+    } else {
+        cfg_if! {
+            if #[cfg(stm32h7)] {
+                let lec = err.lec();
+            } else {
+                let lec = err.lec().to_bits();
+            }
+        }
+        if let Ok(err) = LastErrorCode::try_from(lec) {
+            return BusError::try_from(err);
+        }
+    }
+    None
+}
+
+impl<'d, T: Instance> Fdcan<'d, T, fdcan::ConfigMode> {
+    /// Creates a new Fdcan instance, keeping the peripheral in sleep mode.
+    /// You must call [Fdcan::enable_non_blocking] to use the peripheral.
+    pub fn new(
+        peri: impl Peripheral<P = T> + 'd,
+        rx: impl Peripheral<P = impl RxPin<T>> + 'd,
+        tx: impl Peripheral<P = impl TxPin<T>> + 'd,
+        _irqs: impl interrupt::typelevel::Binding<T::IT0Interrupt, IT0InterruptHandler<T>>
+            + interrupt::typelevel::Binding<T::IT1Interrupt, IT1InterruptHandler<T>>
+            + 'd,
+    ) -> Fdcan<'d, T, fdcan::ConfigMode> {
+        into_ref!(peri, rx, tx);
+
+        rx.set_as_af(rx.af_num(), AFType::Input);
+        tx.set_as_af(tx.af_num(), AFType::OutputPushPull);
+
+        T::enable_and_reset();
+
+        rx.set_as_af(rx.af_num(), AFType::Input);
+        tx.set_as_af(tx.af_num(), AFType::OutputPushPull);
+
+        let mut can = fdcan::FdCan::new(FdcanInstance(peri)).into_config_mode();
+
+        T::configure_msg_ram();
+        unsafe {
+            // Enable timestamping
+            #[cfg(not(stm32h7))]
+            T::regs()
+                .tscc()
+                .write(|w| w.set_tss(stm32_metapac::can::vals::Tss::INCREMENT));
+            #[cfg(stm32h7)]
+            T::regs().tscc().write(|w| w.set_tss(0x01));
+
+            T::IT0Interrupt::unpend(); // Not unsafe
+            T::IT0Interrupt::enable();
+
+            T::IT1Interrupt::unpend(); // Not unsafe
+            T::IT1Interrupt::enable();
+
+            // this isn't really documented in the reference manual
+            // but corresponding txbtie bit has to be set for the TC (TxComplete) interrupt to fire
+            T::regs().txbtie().write(|w| w.0 = 0xffff_ffff);
+        }
+
+        can.enable_interrupt(fdcan::interrupt::Interrupt::RxFifo0NewMsg);
+        can.enable_interrupt(fdcan::interrupt::Interrupt::RxFifo1NewMsg);
+        can.enable_interrupt(fdcan::interrupt::Interrupt::TxComplete);
+        can.enable_interrupt_line(fdcan::interrupt::InterruptLine::_0, true);
+        can.enable_interrupt_line(fdcan::interrupt::InterruptLine::_1, true);
+
+        let ns_per_timer_tick = calc_ns_per_timer_tick::<T>(can.get_config().frame_transmit);
+        Self { can, ns_per_timer_tick }
+    }
+
+    /// Configures the bit timings calculated from supplied bitrate.
+    pub fn set_bitrate(&mut self, bitrate: u32) {
+        let bit_timing = util::calc_can_timings(T::frequency(), bitrate).unwrap();
+        self.can.set_nominal_bit_timing(config::NominalBitTiming {
+            sync_jump_width: bit_timing.sync_jump_width,
+            prescaler: bit_timing.prescaler,
+            seg1: bit_timing.seg1,
+            seg2: bit_timing.seg2,
+        });
+    }
+}
+
+macro_rules! impl_transition {
+    ($from_mode:ident, $to_mode:ident, $name:ident, $func: ident) => {
+        impl<'d, T: Instance> Fdcan<'d, T, fdcan::$from_mode> {
+            /// Transition from $from_mode:ident mode to $to_mode:ident mode
+            pub fn $name(self) -> Fdcan<'d, T, fdcan::$to_mode> {
+                let ns_per_timer_tick = calc_ns_per_timer_tick::<T>(self.can.get_config().frame_transmit);
+                Fdcan {
+                    can: self.can.$func(),
+                    ns_per_timer_tick,
+                }
+            }
+        }
+    };
+}
+
+impl_transition!(PoweredDownMode, ConfigMode, into_config_mode, into_config_mode);
+impl_transition!(InternalLoopbackMode, ConfigMode, into_config_mode, into_config_mode);
+
+impl_transition!(ConfigMode, NormalOperationMode, into_normal_mode, into_normal);
+impl_transition!(
+    ConfigMode,
+    ExternalLoopbackMode,
+    into_external_loopback_mode,
+    into_external_loopback
+);
+impl_transition!(
+    ConfigMode,
+    InternalLoopbackMode,
+    into_internal_loopback_mode,
+    into_internal_loopback
+);
+
+impl<'d, T: Instance, M: FdcanOperatingMode> Fdcan<'d, T, M>
+where
+    M: fdcan::Transmit,
+    M: fdcan::Receive,
+{
+    /// Queues the message to be sent but exerts backpressure.  If a lower-priority
+    /// frame is dropped from the mailbox, it is returned.  If no lower-priority frames
+    /// can be replaced, this call asynchronously waits for a frame to be successfully
+    /// transmitted, then tries again.
+    pub async fn write(&mut self, frame: &TxFrame) -> Option<TxFrame> {
+        poll_fn(|cx| {
+            T::state().tx_waker.register(cx.waker());
+            if let Ok(dropped) = self
+                .can
+                .transmit_preserve(frame.header, &frame.data.bytes, &mut |_, hdr, data32| {
+                    TxFrame::from_preserved(hdr, data32)
+                })
+            {
+                return Poll::Ready(dropped.flatten());
+            }
+
+            // Couldn't replace any lower priority frames.  Need to wait for some mailboxes
+            // to clear.
+            Poll::Pending
+        })
+        .await
+    }
+
+    /// Flush one of the TX mailboxes.
+    pub async fn flush(&self, mb: fdcan::Mailbox) {
+        poll_fn(|cx| {
+            T::state().tx_waker.register(cx.waker());
+
+            let idx: u8 = mb.into();
+            let idx = 1 << idx;
+            if !T::regs().txbrp().read().trp(idx) {
+                return Poll::Ready(());
+            }
+
+            Poll::Pending
+        })
+        .await;
+    }
+
+    /// Returns the next received message frame
+    pub async fn read(&mut self) -> Result<RxFrame, BusError> {
+        poll_fn(|cx| {
+            T::state().err_waker.register(cx.waker());
+            T::state().rx_waker.register(cx.waker());
+
+            let mut buffer: [u8; 64] = [0; 64];
+            if let Ok(rx) = self.can.receive0(&mut buffer) {
+                // rx: fdcan::ReceiveOverrun<RxFrameInfo>
+                // TODO: report overrun?
+                //  for now we just drop it
+
+                let frame: RxFrame = RxFrame::new(
+                    rx.unwrap(),
+                    &buffer,
+                    #[cfg(feature = "time")]
+                    calc_timestamp::<T>(self.ns_per_timer_tick, rx.unwrap().time_stamp),
+                );
+                return Poll::Ready(Ok(frame));
+            } else if let Ok(rx) = self.can.receive1(&mut buffer) {
+                // rx: fdcan::ReceiveOverrun<RxFrameInfo>
+                // TODO: report overrun?
+                //  for now we just drop it
+
+                let frame: RxFrame = RxFrame::new(
+                    rx.unwrap(),
+                    &buffer,
+                    #[cfg(feature = "time")]
+                    calc_timestamp::<T>(self.ns_per_timer_tick, rx.unwrap().time_stamp),
+                );
+                return Poll::Ready(Ok(frame));
+            } else if let Some(err) = curr_error::<T>() {
+                // TODO: this is probably wrong
+                return Poll::Ready(Err(err));
+            }
+            Poll::Pending
+        })
+        .await
+    }
+
+    /// Split instance into separate Tx(write) and Rx(read) portions
+    pub fn split<'c>(&'c mut self) -> (FdcanTx<'c, 'd, T, M>, FdcanRx<'c, 'd, T, M>) {
+        let (mut _control, tx, rx0, rx1) = self.can.split_by_ref();
+        (
+            FdcanTx { _control, tx },
+            FdcanRx {
+                rx0,
+                rx1,
+                ns_per_timer_tick: self.ns_per_timer_tick,
+            },
+        )
+    }
+}
+
+/// FDCAN Tx only Instance
+pub struct FdcanTx<'c, 'd, T: Instance, M: fdcan::Transmit> {
+    _control: &'c mut fdcan::FdCanControl<FdcanInstance<'d, T>, M>,
+    tx: &'c mut fdcan::Tx<FdcanInstance<'d, T>, M>,
+}
+
+impl<'c, 'd, T: Instance, M: fdcan::Transmit> FdcanTx<'c, 'd, T, M> {
+    /// Queues the message to be sent but exerts backpressure.  If a lower-priority
+    /// frame is dropped from the mailbox, it is returned.  If no lower-priority frames
+    /// can be replaced, this call asynchronously waits for a frame to be successfully
+    /// transmitted, then tries again.
+    pub async fn write(&mut self, frame: &TxFrame) -> Option<TxFrame> {
+        poll_fn(|cx| {
+            T::state().tx_waker.register(cx.waker());
+            if let Ok(dropped) = self
+                .tx
+                .transmit_preserve(frame.header, &frame.data.bytes, &mut |_, hdr, data32| {
+                    TxFrame::from_preserved(hdr, data32)
+                })
+            {
+                return Poll::Ready(dropped.flatten());
+            }
+
+            // Couldn't replace any lower priority frames.  Need to wait for some mailboxes
+            // to clear.
+            Poll::Pending
+        })
+        .await
+    }
+}
+
+/// FDCAN Rx only Instance
+#[allow(dead_code)]
+pub struct FdcanRx<'c, 'd, T: Instance, M: fdcan::Receive> {
+    rx0: &'c mut fdcan::Rx<FdcanInstance<'d, T>, M, fdcan::Fifo0>,
+    rx1: &'c mut fdcan::Rx<FdcanInstance<'d, T>, M, fdcan::Fifo1>,
+    ns_per_timer_tick: u64, // For FDCAN internal timer
+}
+
+impl<'c, 'd, T: Instance, M: fdcan::Receive> FdcanRx<'c, 'd, T, M> {
+    /// Returns the next received message frame
+    pub async fn read(&mut self) -> Result<RxFrame, BusError> {
+        poll_fn(|cx| {
+            T::state().err_waker.register(cx.waker());
+            T::state().rx_waker.register(cx.waker());
+
+            let mut buffer: [u8; 64] = [0; 64];
+            if let Ok(rx) = self.rx0.receive(&mut buffer) {
+                // rx: fdcan::ReceiveOverrun<RxFrameInfo>
+                // TODO: report overrun?
+                //  for now we just drop it
+                let frame: RxFrame = RxFrame::new(
+                    rx.unwrap(),
+                    &buffer,
+                    #[cfg(feature = "time")]
+                    calc_timestamp::<T>(self.ns_per_timer_tick, rx.unwrap().time_stamp),
+                );
+                return Poll::Ready(Ok(frame));
+            } else if let Ok(rx) = self.rx1.receive(&mut buffer) {
+                // rx: fdcan::ReceiveOverrun<RxFrameInfo>
+                // TODO: report overrun?
+                //  for now we just drop it
+                let frame: RxFrame = RxFrame::new(
+                    rx.unwrap(),
+                    &buffer,
+                    #[cfg(feature = "time")]
+                    calc_timestamp::<T>(self.ns_per_timer_tick, rx.unwrap().time_stamp),
+                );
+                return Poll::Ready(Ok(frame));
+            } else if let Some(err) = curr_error::<T>() {
+                // TODO: this is probably wrong
+                return Poll::Ready(Err(err));
+            }
+
+            Poll::Pending
+        })
+        .await
+    }
+}
+impl<'d, T: Instance, M: FdcanOperatingMode> Deref for Fdcan<'d, T, M> {
+    type Target = fdcan::FdCan<FdcanInstance<'d, T>, M>;
+
+    fn deref(&self) -> &Self::Target {
+        &self.can
+    }
+}
+
+impl<'d, T: Instance, M: FdcanOperatingMode> DerefMut for Fdcan<'d, T, M> {
+    fn deref_mut(&mut self) -> &mut Self::Target {
+        &mut self.can
+    }
+}
 
 pub(crate) mod sealed {
-    use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
-    use embassy_sync::channel::Channel;
     use embassy_sync::waitqueue::AtomicWaker;
 
     pub struct State {
         pub tx_waker: AtomicWaker,
         pub err_waker: AtomicWaker,
-        pub rx_queue: Channel<CriticalSectionRawMutex, (u16, bxcan::Frame), 32>,
+        pub rx_waker: AtomicWaker,
     }
 
     impl State {
@@ -16,25 +579,122 @@ pub(crate) mod sealed {
             Self {
                 tx_waker: AtomicWaker::new(),
                 err_waker: AtomicWaker::new(),
-                rx_queue: Channel::new(),
+                rx_waker: AtomicWaker::new(),
             }
         }
     }
 
     pub trait Instance {
+        const REGISTERS: *mut fdcan::RegisterBlock;
+        const MSG_RAM: *mut fdcan::message_ram::RegisterBlock;
+        const MSG_RAM_OFFSET: usize;
+
         fn regs() -> &'static crate::pac::can::Fdcan;
         fn state() -> &'static State;
+
+        #[cfg(not(stm32h7))]
+        fn configure_msg_ram() {}
+
+        #[cfg(stm32h7)]
+        fn configure_msg_ram() {
+            let r = Self::regs();
+
+            use fdcan::message_ram::*;
+            let mut offset_words = Self::MSG_RAM_OFFSET as u16;
+
+            // 11-bit filter
+            r.sidfc().modify(|w| w.set_flssa(offset_words));
+            offset_words += STANDARD_FILTER_MAX as u16;
+
+            // 29-bit filter
+            r.xidfc().modify(|w| w.set_flesa(offset_words));
+            offset_words += 2 * EXTENDED_FILTER_MAX as u16;
+
+            // Rx FIFO 0 and 1
+            for i in 0..=1 {
+                r.rxfc(i).modify(|w| {
+                    w.set_fsa(offset_words);
+                    w.set_fs(RX_FIFO_MAX);
+                    w.set_fwm(RX_FIFO_MAX);
+                });
+                offset_words += 18 * RX_FIFO_MAX as u16;
+            }
+
+            // Rx buffer - see below
+            // Tx event FIFO
+            r.txefc().modify(|w| {
+                w.set_efsa(offset_words);
+                w.set_efs(TX_EVENT_MAX);
+                w.set_efwm(TX_EVENT_MAX);
+            });
+            offset_words += 2 * TX_EVENT_MAX as u16;
+
+            // Tx buffers
+            r.txbc().modify(|w| {
+                w.set_tbsa(offset_words);
+                w.set_tfqs(TX_FIFO_MAX);
+            });
+            offset_words += 18 * TX_FIFO_MAX as u16;
+
+            // Rx Buffer - not used
+            r.rxbc().modify(|w| {
+                w.set_rbsa(offset_words);
+            });
+
+            // TX event FIFO?
+            // Trigger memory?
+
+            // Set the element sizes to 16 bytes
+            r.rxesc().modify(|w| {
+                w.set_rbds(0b111);
+                for i in 0..=1 {
+                    w.set_fds(i, 0b111);
+                }
+            });
+            r.txesc().modify(|w| {
+                w.set_tbds(0b111);
+            })
+        }
     }
 }
 
-/// Interruptable FDCAN instance.
-pub trait InterruptableInstance {}
-/// FDCAN instance.
-pub trait Instance: sealed::Instance + InterruptableInstance + 'static {}
+/// Trait for FDCAN interrupt channel 0
+pub trait IT0Instance {
+    /// Type for FDCAN interrupt channel 0
+    type IT0Interrupt: crate::interrupt::typelevel::Interrupt;
+}
 
-foreach_peripheral!(
-    (can, $inst:ident) => {
+/// Trait for FDCAN interrupt channel 1
+pub trait IT1Instance {
+    /// Type for FDCAN interrupt channel 1
+    type IT1Interrupt: crate::interrupt::typelevel::Interrupt;
+}
+
+/// InterruptableInstance trait
+pub trait InterruptableInstance: IT0Instance + IT1Instance {}
+/// Instance trait
+pub trait Instance: sealed::Instance + RccPeripheral + InterruptableInstance + 'static {}
+/// Fdcan Instance struct
+pub struct FdcanInstance<'a, T>(PeripheralRef<'a, T>);
+
+unsafe impl<'d, T: Instance> fdcan::message_ram::Instance for FdcanInstance<'d, T> {
+    const MSG_RAM: *mut RegisterBlock = T::MSG_RAM;
+}
+
+unsafe impl<'d, T: Instance> fdcan::Instance for FdcanInstance<'d, T>
+where
+    FdcanInstance<'d, T>: fdcan::message_ram::Instance,
+{
+    const REGISTERS: *mut fdcan::RegisterBlock = T::REGISTERS;
+}
+
+macro_rules! impl_fdcan {
+    ($inst:ident, $msg_ram_inst:ident, $msg_ram_offset:literal) => {
         impl sealed::Instance for peripherals::$inst {
+            const REGISTERS: *mut fdcan::RegisterBlock = crate::pac::$inst.as_ptr() as *mut _;
+            const MSG_RAM: *mut fdcan::message_ram::RegisterBlock = crate::pac::$msg_ram_inst.as_ptr() as *mut _;
+            const MSG_RAM_OFFSET: usize = $msg_ram_offset;
+
             fn regs() -> &'static crate::pac::can::Fdcan {
                 &crate::pac::$inst
             }
@@ -47,8 +707,40 @@ foreach_peripheral!(
 
         impl Instance for peripherals::$inst {}
 
+        foreach_interrupt!(
+            ($inst,can,FDCAN,IT0,$irq:ident) => {
+                impl IT0Instance for peripherals::$inst {
+                    type IT0Interrupt = crate::interrupt::typelevel::$irq;
+                }
+            };
+            ($inst,can,FDCAN,IT1,$irq:ident) => {
+                impl IT1Instance for peripherals::$inst {
+                    type IT1Interrupt = crate::interrupt::typelevel::$irq;
+                }
+            };
+        );
+
         impl InterruptableInstance for peripherals::$inst {}
     };
+
+    ($inst:ident, $msg_ram_inst:ident) => {
+        impl_fdcan!($inst, $msg_ram_inst, 0);
+    };
+}
+
+#[cfg(not(stm32h7))]
+foreach_peripheral!(
+    (can, FDCAN) => { impl_fdcan!(FDCAN, FDCANRAM); };
+    (can, FDCAN1) => { impl_fdcan!(FDCAN1, FDCANRAM1); };
+    (can, FDCAN2) => { impl_fdcan!(FDCAN2, FDCANRAM2); };
+    (can, FDCAN3) => { impl_fdcan!(FDCAN3, FDCANRAM3); };
+);
+
+#[cfg(stm32h7)]
+foreach_peripheral!(
+    (can, FDCAN1) => { impl_fdcan!(FDCAN1, FDCANRAM, 0x0000); };
+    (can, FDCAN2) => { impl_fdcan!(FDCAN2, FDCANRAM, 0x0C00); };
+    (can, FDCAN3) => { impl_fdcan!(FDCAN3, FDCANRAM, 0x1800); };
 );
 
 pin_trait!(RxPin, Instance);
diff --git a/embassy-stm32/src/can/util.rs b/embassy-stm32/src/can/util.rs
new file mode 100644
index 000000000..fcdbbad62
--- /dev/null
+++ b/embassy-stm32/src/can/util.rs
@@ -0,0 +1,117 @@
+//! Utility functions shared between CAN controller types.
+
+use core::num::{NonZeroU16, NonZeroU8};
+
+/// Shared struct to represent bit timings used by calc_can_timings.
+#[derive(Clone, Copy, Debug)]
+pub struct NominalBitTiming {
+    /// Value by which the oscillator frequency is divided for generating the bit time quanta. The bit
+    /// time is built up from a multiple of this quanta. Valid values are 1 to 512.
+    pub prescaler: NonZeroU16,
+    /// Valid values are 1 to 128.
+    pub seg1: NonZeroU8,
+    /// Valid values are 1 to 255.
+    pub seg2: NonZeroU8,
+    /// Valid values are 1 to 128.
+    pub sync_jump_width: NonZeroU8,
+}
+
+/// Calculate nominal CAN bit timing based on CAN bitrate and periphial clock frequency
+pub fn calc_can_timings(periph_clock: crate::time::Hertz, can_bitrate: u32) -> Option<NominalBitTiming> {
+    const BS1_MAX: u8 = 16;
+    const BS2_MAX: u8 = 8;
+    const MAX_SAMPLE_POINT_PERMILL: u16 = 900;
+
+    let periph_clock = periph_clock.0;
+
+    if can_bitrate < 1000 {
+        return None;
+    }
+
+    // Ref. "Automatic Baudrate Detection in CANopen Networks", U. Koppe, MicroControl GmbH & Co. KG
+    //      CAN in Automation, 2003
+    //
+    // According to the source, optimal quanta per bit are:
+    //   Bitrate        Optimal Maximum
+    //   1000 kbps      8       10
+    //   500  kbps      16      17
+    //   250  kbps      16      17
+    //   125  kbps      16      17
+    let max_quanta_per_bit: u8 = if can_bitrate >= 1_000_000 { 10 } else { 17 };
+
+    // Computing (prescaler * BS):
+    //   BITRATE = 1 / (PRESCALER * (1 / PCLK) * (1 + BS1 + BS2))       -- See the Reference Manual
+    //   BITRATE = PCLK / (PRESCALER * (1 + BS1 + BS2))                 -- Simplified
+    // let:
+    //   BS = 1 + BS1 + BS2                                             -- Number of time quanta per bit
+    //   PRESCALER_BS = PRESCALER * BS
+    // ==>
+    //   PRESCALER_BS = PCLK / BITRATE
+    let prescaler_bs = periph_clock / can_bitrate;
+
+    // Searching for such prescaler value so that the number of quanta per bit is highest.
+    let mut bs1_bs2_sum = max_quanta_per_bit - 1;
+    while (prescaler_bs % (1 + bs1_bs2_sum) as u32) != 0 {
+        if bs1_bs2_sum <= 2 {
+            return None; // No solution
+        }
+        bs1_bs2_sum -= 1;
+    }
+
+    let prescaler = prescaler_bs / (1 + bs1_bs2_sum) as u32;
+    if (prescaler < 1) || (prescaler > 1024) {
+        return None; // No solution
+    }
+
+    // Now we have a constraint: (BS1 + BS2) == bs1_bs2_sum.
+    // We need to find such values so that the sample point is as close as possible to the optimal value,
+    // which is 87.5%, which is 7/8.
+    //
+    //   Solve[(1 + bs1)/(1 + bs1 + bs2) == 7/8, bs2]  (* Where 7/8 is 0.875, the recommended sample point location *)
+    //   {{bs2 -> (1 + bs1)/7}}
+    //
+    // Hence:
+    //   bs2 = (1 + bs1) / 7
+    //   bs1 = (7 * bs1_bs2_sum - 1) / 8
+    //
+    // Sample point location can be computed as follows:
+    //   Sample point location = (1 + bs1) / (1 + bs1 + bs2)
+    //
+    // Since the optimal solution is so close to the maximum, we prepare two solutions, and then pick the best one:
+    //   - With rounding to nearest
+    //   - With rounding to zero
+    let mut bs1 = ((7 * bs1_bs2_sum - 1) + 4) / 8; // Trying rounding to nearest first
+    let mut bs2 = bs1_bs2_sum - bs1;
+    core::assert!(bs1_bs2_sum > bs1);
+
+    let sample_point_permill = 1000 * ((1 + bs1) / (1 + bs1 + bs2)) as u16;
+    if sample_point_permill > MAX_SAMPLE_POINT_PERMILL {
+        // Nope, too far; now rounding to zero
+        bs1 = (7 * bs1_bs2_sum - 1) / 8;
+        bs2 = bs1_bs2_sum - bs1;
+    }
+
+    // Check is BS1 and BS2 are in range
+    if (bs1 < 1) || (bs1 > BS1_MAX) || (bs2 < 1) || (bs2 > BS2_MAX) {
+        return None;
+    }
+
+    // Check if final bitrate matches the requested
+    if can_bitrate != (periph_clock / (prescaler * (1 + bs1 + bs2) as u32)) {
+        return None;
+    }
+
+    // One is recommended by DS-015, CANOpen, and DeviceNet
+    let sync_jump_width = core::num::NonZeroU8::new(1)?;
+
+    let seg1 = core::num::NonZeroU8::new(bs1)?;
+    let seg2 = core::num::NonZeroU8::new(bs2)?;
+    let nz_prescaler = core::num::NonZeroU16::new(prescaler as u16)?;
+
+    Some(NominalBitTiming {
+        sync_jump_width,
+        prescaler: nz_prescaler,
+        seg1,
+        seg2,
+    })
+}
diff --git a/embassy-stm32/src/dac/mod.rs b/embassy-stm32/src/dac/mod.rs
index 31dedf06e..60f9404c2 100644
--- a/embassy-stm32/src/dac/mod.rs
+++ b/embassy-stm32/src/dac/mod.rs
@@ -504,29 +504,6 @@ pub trait DacPin<T: Instance, const C: u8>: crate::gpio::Pin + 'static {}
 
 foreach_peripheral!(
     (dac, $inst:ident) => {
-        // H7 uses single bit for both DAC1 and DAC2, this is a hack until a proper fix is implemented
-        #[cfg(any(rcc_h7, rcc_h7rm0433))]
-        impl crate::rcc::sealed::RccPeripheral for peripherals::$inst {
-            fn frequency() -> crate::time::Hertz {
-                critical_section::with(|_| unsafe { crate::rcc::get_freqs().pclk1 })
-            }
-
-            fn enable_and_reset_with_cs(_cs: critical_section::CriticalSection) {
-                // TODO: Increment refcount?
-                crate::pac::RCC.apb1lrstr().modify(|w| w.set_dac12rst(true));
-                crate::pac::RCC.apb1lrstr().modify(|w| w.set_dac12rst(false));
-                crate::pac::RCC.apb1lenr().modify(|w| w.set_dac12en(true));
-            }
-
-            fn disable_with_cs(_cs: critical_section::CriticalSection) {
-                // TODO: Decrement refcount?
-                crate::pac::RCC.apb1lenr().modify(|w| w.set_dac12en(false))
-            }
-        }
-
-        #[cfg(any(rcc_h7, rcc_h7rm0433))]
-        impl crate::rcc::RccPeripheral for peripherals::$inst {}
-
         impl crate::dac::sealed::Instance for peripherals::$inst {
             fn regs() -> &'static crate::pac::dac::Dac {
                 &crate::pac::$inst
diff --git a/embassy-stm32/src/eth/mod.rs b/embassy-stm32/src/eth/mod.rs
index 448405507..71fe09c3f 100644
--- a/embassy-stm32/src/eth/mod.rs
+++ b/embassy-stm32/src/eth/mod.rs
@@ -13,6 +13,7 @@ use embassy_net_driver::{Capabilities, HardwareAddress, LinkState};
 use embassy_sync::waitqueue::AtomicWaker;
 
 pub use self::_version::{InterruptHandler, *};
+use crate::rcc::RccPeripheral;
 
 #[allow(unused)]
 const MTU: usize = 1514;
@@ -183,7 +184,7 @@ pub(crate) mod sealed {
 }
 
 /// Ethernet instance.
-pub trait Instance: sealed::Instance + Send + 'static {}
+pub trait Instance: sealed::Instance + RccPeripheral + Send + 'static {}
 
 impl sealed::Instance for crate::peripherals::ETH {
     fn regs() -> crate::pac::eth::Eth {
@@ -192,12 +193,19 @@ impl sealed::Instance for crate::peripherals::ETH {
 }
 impl Instance for crate::peripherals::ETH {}
 
+pin_trait!(RXClkPin, Instance);
+pin_trait!(TXClkPin, Instance);
 pin_trait!(RefClkPin, Instance);
 pin_trait!(MDIOPin, Instance);
 pin_trait!(MDCPin, Instance);
+pin_trait!(RXDVPin, Instance);
 pin_trait!(CRSPin, Instance);
 pin_trait!(RXD0Pin, Instance);
 pin_trait!(RXD1Pin, Instance);
+pin_trait!(RXD2Pin, Instance);
+pin_trait!(RXD3Pin, Instance);
 pin_trait!(TXD0Pin, Instance);
 pin_trait!(TXD1Pin, Instance);
+pin_trait!(TXD2Pin, Instance);
+pin_trait!(TXD3Pin, Instance);
 pin_trait!(TXEnPin, Instance);
diff --git a/embassy-stm32/src/eth/v1/mod.rs b/embassy-stm32/src/eth/v1/mod.rs
index 2ce5b3927..e5b7b0452 100644
--- a/embassy-stm32/src/eth/v1/mod.rs
+++ b/embassy-stm32/src/eth/v1/mod.rs
@@ -20,6 +20,7 @@ use crate::pac::AFIO;
 #[cfg(any(eth_v1b, eth_v1c))]
 use crate::pac::SYSCFG;
 use crate::pac::{ETH, RCC};
+use crate::rcc::sealed::RccPeripheral;
 use crate::{interrupt, Peripheral};
 
 /// Interrupt handler.
@@ -191,8 +192,7 @@ impl<'d, T: Instance, P: PHY> Ethernet<'d, T, P> {
 
         // TODO MTU size setting not found for v1 ethernet, check if correct
 
-        // NOTE(unsafe) We got the peripheral singleton, which means that `rcc::init` was called
-        let hclk = unsafe { crate::rcc::get_freqs() }.hclk1;
+        let hclk = <T as RccPeripheral>::frequency();
         let hclk_mhz = hclk.0 / 1_000_000;
 
         // Set the MDC clock frequency in the range 1MHz - 2.5MHz
diff --git a/embassy-stm32/src/eth/v2/descriptors.rs b/embassy-stm32/src/eth/v2/descriptors.rs
index 01ea8e574..645bfdb14 100644
--- a/embassy-stm32/src/eth/v2/descriptors.rs
+++ b/embassy-stm32/src/eth/v2/descriptors.rs
@@ -129,7 +129,7 @@ impl<'a> TDesRing<'a> {
 
 /// Receive Descriptor representation
 ///
-/// * rdes0: recieve buffer address
+/// * rdes0: receive buffer address
 /// * rdes1:
 /// * rdes2:
 /// * rdes3: OWN and Status
diff --git a/embassy-stm32/src/eth/v2/mod.rs b/embassy-stm32/src/eth/v2/mod.rs
index 59745cba0..8d69561d4 100644
--- a/embassy-stm32/src/eth/v2/mod.rs
+++ b/embassy-stm32/src/eth/v2/mod.rs
@@ -11,6 +11,7 @@ use crate::gpio::sealed::{AFType, Pin as _};
 use crate::gpio::{AnyPin, Speed};
 use crate::interrupt::InterruptExt;
 use crate::pac::ETH;
+use crate::rcc::sealed::RccPeripheral;
 use crate::{interrupt, Peripheral};
 
 /// Interrupt handler.
@@ -39,12 +40,18 @@ pub struct Ethernet<'d, T: Instance, P: PHY> {
     _peri: PeripheralRef<'d, T>,
     pub(crate) tx: TDesRing<'d>,
     pub(crate) rx: RDesRing<'d>,
-    pins: [PeripheralRef<'d, AnyPin>; 9],
+    pins: Pins<'d>,
     pub(crate) phy: P,
     pub(crate) station_management: EthernetStationManagement<T>,
     pub(crate) mac_addr: [u8; 6],
 }
 
+/// Pins of ethernet driver.
+enum Pins<'d> {
+    Rmii([PeripheralRef<'d, AnyPin>; 9]),
+    Mii([PeripheralRef<'d, AnyPin>; 14]),
+}
+
 macro_rules! config_pins {
     ($($pin:ident),*) => {
         critical_section::with(|_| {
@@ -57,11 +64,11 @@ macro_rules! config_pins {
 }
 
 impl<'d, T: Instance, P: PHY> Ethernet<'d, T, P> {
-    /// Create a new Ethernet driver.
+    /// Create a new RMII ethernet driver using 9 pins.
     pub fn new<const TX: usize, const RX: usize>(
         queue: &'d mut PacketQueue<TX, RX>,
         peri: impl Peripheral<P = T> + 'd,
-        _irq: impl interrupt::typelevel::Binding<interrupt::typelevel::ETH, InterruptHandler> + 'd,
+        irq: impl interrupt::typelevel::Binding<interrupt::typelevel::ETH, InterruptHandler> + 'd,
         ref_clk: impl Peripheral<P = impl RefClkPin<T>> + 'd,
         mdio: impl Peripheral<P = impl MDIOPin<T>> + 'd,
         mdc: impl Peripheral<P = impl MDCPin<T>> + 'd,
@@ -74,8 +81,6 @@ impl<'d, T: Instance, P: PHY> Ethernet<'d, T, P> {
         phy: P,
         mac_addr: [u8; 6],
     ) -> Self {
-        into_ref!(peri, ref_clk, mdio, mdc, crs, rx_d0, rx_d1, tx_d0, tx_d1, tx_en);
-
         // Enable the necessary Clocks
         #[cfg(not(rcc_h5))]
         critical_section::with(|_| {
@@ -85,7 +90,6 @@ impl<'d, T: Instance, P: PHY> Ethernet<'d, T, P> {
                 w.set_eth1rxen(true);
             });
 
-            // RMII
             crate::pac::SYSCFG.pmcr().modify(|w| w.set_epis(0b100));
         });
 
@@ -99,14 +103,110 @@ impl<'d, T: Instance, P: PHY> Ethernet<'d, T, P> {
                 w.set_ethrxen(true);
             });
 
-            // RMII
             crate::pac::SYSCFG
                 .pmcr()
                 .modify(|w| w.set_eth_sel_phy(crate::pac::syscfg::vals::EthSelPhy::B_0X4));
         });
 
+        into_ref!(ref_clk, mdio, mdc, crs, rx_d0, rx_d1, tx_d0, tx_d1, tx_en);
         config_pins!(ref_clk, mdio, mdc, crs, rx_d0, rx_d1, tx_d0, tx_d1, tx_en);
 
+        let pins = Pins::Rmii([
+            ref_clk.map_into(),
+            mdio.map_into(),
+            mdc.map_into(),
+            crs.map_into(),
+            rx_d0.map_into(),
+            rx_d1.map_into(),
+            tx_d0.map_into(),
+            tx_d1.map_into(),
+            tx_en.map_into(),
+        ]);
+
+        Self::new_inner(queue, peri, irq, pins, phy, mac_addr)
+    }
+
+    /// Create a new MII ethernet driver using 14 pins.
+    pub fn new_mii<const TX: usize, const RX: usize>(
+        queue: &'d mut PacketQueue<TX, RX>,
+        peri: impl Peripheral<P = T> + 'd,
+        irq: impl interrupt::typelevel::Binding<interrupt::typelevel::ETH, InterruptHandler> + 'd,
+        rx_clk: impl Peripheral<P = impl RXClkPin<T>> + 'd,
+        tx_clk: impl Peripheral<P = impl TXClkPin<T>> + 'd,
+        mdio: impl Peripheral<P = impl MDIOPin<T>> + 'd,
+        mdc: impl Peripheral<P = impl MDCPin<T>> + 'd,
+        rxdv: impl Peripheral<P = impl RXDVPin<T>> + 'd,
+        rx_d0: impl Peripheral<P = impl RXD0Pin<T>> + 'd,
+        rx_d1: impl Peripheral<P = impl RXD1Pin<T>> + 'd,
+        rx_d2: impl Peripheral<P = impl RXD2Pin<T>> + 'd,
+        rx_d3: impl Peripheral<P = impl RXD3Pin<T>> + 'd,
+        tx_d0: impl Peripheral<P = impl TXD0Pin<T>> + 'd,
+        tx_d1: impl Peripheral<P = impl TXD1Pin<T>> + 'd,
+        tx_d2: impl Peripheral<P = impl TXD2Pin<T>> + 'd,
+        tx_d3: impl Peripheral<P = impl TXD3Pin<T>> + 'd,
+        tx_en: impl Peripheral<P = impl TXEnPin<T>> + 'd,
+        phy: P,
+        mac_addr: [u8; 6],
+    ) -> Self {
+        // Enable necessary clocks.
+        #[cfg(not(rcc_h5))]
+        critical_section::with(|_| {
+            crate::pac::RCC.ahb1enr().modify(|w| {
+                w.set_eth1macen(true);
+                w.set_eth1txen(true);
+                w.set_eth1rxen(true);
+            });
+
+            crate::pac::SYSCFG.pmcr().modify(|w| w.set_epis(0b000));
+        });
+
+        #[cfg(rcc_h5)]
+        critical_section::with(|_| {
+            crate::pac::RCC.apb3enr().modify(|w| w.set_sbsen(true));
+
+            crate::pac::RCC.ahb1enr().modify(|w| {
+                w.set_ethen(true);
+                w.set_ethtxen(true);
+                w.set_ethrxen(true);
+            });
+
+            // TODO: This is for RMII - what would MII need here?
+            crate::pac::SYSCFG
+                .pmcr()
+                .modify(|w| w.set_eth_sel_phy(crate::pac::syscfg::vals::EthSelPhy::B_0X4));
+        });
+
+        into_ref!(rx_clk, tx_clk, mdio, mdc, rxdv, rx_d0, rx_d1, rx_d2, rx_d3, tx_d0, tx_d1, tx_d2, tx_d3, tx_en);
+        config_pins!(rx_clk, tx_clk, mdio, mdc, rxdv, rx_d0, rx_d1, rx_d2, rx_d3, tx_d0, tx_d1, tx_d2, tx_d3, tx_en);
+
+        let pins = Pins::Mii([
+            rx_clk.map_into(),
+            tx_clk.map_into(),
+            mdio.map_into(),
+            mdc.map_into(),
+            rxdv.map_into(),
+            rx_d0.map_into(),
+            rx_d1.map_into(),
+            rx_d2.map_into(),
+            rx_d3.map_into(),
+            tx_d0.map_into(),
+            tx_d1.map_into(),
+            tx_d2.map_into(),
+            tx_d3.map_into(),
+            tx_en.map_into(),
+        ]);
+
+        Self::new_inner(queue, peri, irq, pins, phy, mac_addr)
+    }
+
+    fn new_inner<const TX: usize, const RX: usize>(
+        queue: &'d mut PacketQueue<TX, RX>,
+        peri: impl Peripheral<P = T> + 'd,
+        _irq: impl interrupt::typelevel::Binding<interrupt::typelevel::ETH, InterruptHandler> + 'd,
+        pins: Pins<'d>,
+        phy: P,
+        mac_addr: [u8; 6],
+    ) -> Self {
         let dma = ETH.ethernet_dma();
         let mac = ETH.ethernet_mac();
         let mtl = ETH.ethernet_mtl();
@@ -165,8 +265,7 @@ impl<'d, T: Instance, P: PHY> Ethernet<'d, T, P> {
             w.set_rbsz(RX_BUFFER_SIZE as u16);
         });
 
-        // NOTE(unsafe) We got the peripheral singleton, which means that `rcc::init` was called
-        let hclk = unsafe { crate::rcc::get_freqs() }.hclk1;
+        let hclk = <T as RccPeripheral>::frequency();
         let hclk_mhz = hclk.0 / 1_000_000;
 
         // Set the MDC clock frequency in the range 1MHz - 2.5MHz
@@ -182,24 +281,12 @@ impl<'d, T: Instance, P: PHY> Ethernet<'d, T, P> {
             }
         };
 
-        let pins = [
-            ref_clk.map_into(),
-            mdio.map_into(),
-            mdc.map_into(),
-            crs.map_into(),
-            rx_d0.map_into(),
-            rx_d1.map_into(),
-            tx_d0.map_into(),
-            tx_d1.map_into(),
-            tx_en.map_into(),
-        ];
-
         let mut this = Self {
-            _peri: peri,
+            _peri: peri.into_ref(),
             tx: TDesRing::new(&mut queue.tx_desc, &mut queue.tx_buf),
             rx: RDesRing::new(&mut queue.rx_desc, &mut queue.rx_buf),
             pins,
-            phy: phy,
+            phy,
             station_management: EthernetStationManagement {
                 peri: PhantomData,
                 clock_range: clock_range,
@@ -302,7 +389,10 @@ impl<'d, T: Instance, P: PHY> Drop for Ethernet<'d, T, P> {
         dma.dmacrx_cr().modify(|w| w.set_sr(false));
 
         critical_section::with(|_| {
-            for pin in self.pins.iter_mut() {
+            for pin in match self.pins {
+                Pins::Rmii(ref mut pins) => pins.iter_mut(),
+                Pins::Mii(ref mut pins) => pins.iter_mut(),
+            } {
                 pin.set_as_disconnected();
             }
         })
diff --git a/embassy-stm32/src/hrtim/mod.rs b/embassy-stm32/src/hrtim/mod.rs
index faefaabbc..3ec646fc3 100644
--- a/embassy-stm32/src/hrtim/mod.rs
+++ b/embassy-stm32/src/hrtim/mod.rs
@@ -10,8 +10,6 @@ pub use traits::Instance;
 #[allow(unused_imports)]
 use crate::gpio::sealed::{AFType, Pin};
 use crate::gpio::AnyPin;
-#[cfg(stm32f334)]
-use crate::rcc::get_freqs;
 use crate::time::Hertz;
 use crate::Peripheral;
 
@@ -182,7 +180,7 @@ impl<'d, T: Instance> AdvancedPwm<'d, T> {
         T::enable_and_reset();
 
         #[cfg(stm32f334)]
-        if unsafe { get_freqs() }.hrtim.is_some() {
+        if crate::pac::RCC.cfgr3().read().hrtim1sw() == crate::pac::rcc::vals::Timsw::PLL1_P {
             // Enable and and stabilize the DLL
             T::regs().dllcr().modify(|w| {
                 w.set_cal(true);
diff --git a/embassy-stm32/src/hrtim/traits.rs b/embassy-stm32/src/hrtim/traits.rs
index cfd31c47c..dcc2b9ef4 100644
--- a/embassy-stm32/src/hrtim/traits.rs
+++ b/embassy-stm32/src/hrtim/traits.rs
@@ -80,10 +80,12 @@ pub(crate) mod sealed {
 
         fn set_master_frequency(frequency: Hertz) {
             let f = frequency.0;
-            #[cfg(not(stm32f334))]
+
+            // TODO: wire up HRTIM to the RCC mux infra.
+            //#[cfg(stm32f334)]
+            //let timer_f = unsafe { crate::rcc::get_freqs() }.hrtim.unwrap_or(Self::frequency()).0;
+            //#[cfg(not(stm32f334))]
             let timer_f = Self::frequency().0;
-            #[cfg(stm32f334)]
-            let timer_f = unsafe { crate::rcc::get_freqs() }.hrtim.unwrap_or(Self::frequency()).0;
 
             let psc_min = (timer_f / f) / (u16::MAX as u32 / 32);
             let psc = if Self::regs().isr().read().dllrdy() {
@@ -103,10 +105,12 @@ pub(crate) mod sealed {
 
         fn set_channel_frequency(channel: usize, frequency: Hertz) {
             let f = frequency.0;
-            #[cfg(not(stm32f334))]
+
+            // TODO: wire up HRTIM to the RCC mux infra.
+            //#[cfg(stm32f334)]
+            //let timer_f = unsafe { crate::rcc::get_freqs() }.hrtim.unwrap_or(Self::frequency()).0;
+            //#[cfg(not(stm32f334))]
             let timer_f = Self::frequency().0;
-            #[cfg(stm32f334)]
-            let timer_f = unsafe { crate::rcc::get_freqs() }.hrtim.unwrap_or(Self::frequency()).0;
 
             let psc_min = (timer_f / f) / (u16::MAX as u32 / 32);
             let psc = if Self::regs().isr().read().dllrdy() {
diff --git a/embassy-stm32/src/i2s.rs b/embassy-stm32/src/i2s.rs
index 1f85c0bc5..e9065dce6 100644
--- a/embassy-stm32/src/i2s.rs
+++ b/embassy-stm32/src/i2s.rs
@@ -4,7 +4,6 @@ use embassy_hal_internal::into_ref;
 use crate::gpio::sealed::{AFType, Pin as _};
 use crate::gpio::AnyPin;
 use crate::pac::spi::vals;
-use crate::rcc::get_freqs;
 use crate::spi::{Config as SpiConfig, *};
 use crate::time::Hertz;
 use crate::{Peripheral, PeripheralRef};
@@ -193,10 +192,10 @@ impl<'d, T: Instance, Tx, Rx> I2S<'d, T, Tx, Rx> {
         spi_cfg.frequency = freq;
         let spi = Spi::new_internal(peri, txdma, rxdma, spi_cfg);
 
-        #[cfg(all(rcc_f4, not(stm32f410)))]
-        let pclk = unsafe { get_freqs() }.plli2s1_q.unwrap();
-
-        #[cfg(stm32f410)]
+        // TODO move i2s to the new mux infra.
+        //#[cfg(all(rcc_f4, not(stm32f410)))]
+        //let pclk = unsafe { get_freqs() }.plli2s1_q.unwrap();
+        //#[cfg(stm32f410)]
         let pclk = T::frequency();
 
         let (odd, div) = compute_baud_rate(pclk, freq, config.master_clock, config.format);
diff --git a/embassy-stm32/src/rcc/c0.rs b/embassy-stm32/src/rcc/c0.rs
index 68f029ca0..ca1222185 100644
--- a/embassy-stm32/src/rcc/c0.rs
+++ b/embassy-stm32/src/rcc/c0.rs
@@ -2,7 +2,6 @@ use crate::pac::flash::vals::Latency;
 use crate::pac::rcc::vals::Sw;
 pub use crate::pac::rcc::vals::{Hpre as AHBPrescaler, Hsidiv as HSIPrescaler, Ppre as APBPrescaler};
 use crate::pac::{FLASH, RCC};
-use crate::rcc::{set_freqs, Clocks};
 use crate::time::Hertz;
 
 /// HSI speed
@@ -133,13 +132,13 @@ pub(crate) unsafe fn init(config: Config) {
         }
     };
 
-    set_freqs(Clocks {
+    set_clocks!(
         hsi: None,
         lse: None,
-        sys: sys_clk,
-        hclk1: ahb_freq,
-        pclk1: apb_freq,
-        pclk1_tim: apb_tim_freq,
-        rtc,
-    });
+        sys: Some(sys_clk),
+        hclk1: Some(ahb_freq),
+        pclk1: Some(apb_freq),
+        pclk1_tim: Some(apb_tim_freq),
+        rtc: rtc,
+    );
 }
diff --git a/embassy-stm32/src/rcc/f.rs b/embassy-stm32/src/rcc/f.rs
index 36d9f178f..e306d478d 100644
--- a/embassy-stm32/src/rcc/f.rs
+++ b/embassy-stm32/src/rcc/f.rs
@@ -7,7 +7,6 @@ pub use crate::pac::rcc::vals::{
 #[cfg(any(stm32f4, stm32f7))]
 use crate::pac::PWR;
 use crate::pac::{FLASH, RCC};
-use crate::rcc::{set_freqs, Clocks};
 use crate::time::Hertz;
 
 // TODO: on some F4s, PLLM is shared between all PLLs. Enforce that.
@@ -183,9 +182,9 @@ pub(crate) unsafe fn init(config: Config) {
     };
     let pll = init_pll(PllInstance::Pll, config.pll, &pll_input);
     #[cfg(any(stm32f2, all(stm32f4, not(stm32f410)), stm32f7))]
-    let _plli2s = init_pll(PllInstance::Plli2s, config.plli2s, &pll_input);
+    let plli2s = init_pll(PllInstance::Plli2s, config.plli2s, &pll_input);
     #[cfg(any(stm32f446, stm32f427, stm32f437, stm32f4x9, stm32f7))]
-    let _pllsai = init_pll(PllInstance::Pllsai, config.pllsai, &pll_input);
+    let pllsai = init_pll(PllInstance::Pllsai, config.pllsai, &pll_input);
 
     // Configure sysclk
     let sys = match config.sys {
@@ -257,27 +256,41 @@ pub(crate) unsafe fn init(config: Config) {
     });
     while RCC.cfgr().read().sws() != config.sys {}
 
-    set_freqs(Clocks {
-        sys,
-        hclk1: hclk,
-        hclk2: hclk,
-        hclk3: hclk,
-        pclk1,
-        pclk2,
-        pclk1_tim,
-        pclk2_tim,
-        rtc,
+    set_clocks!(
+        hsi: hsi,
+        hse: hse,
+        lse: None, // TODO
+        lsi: None, // TODO
+        sys: Some(sys),
+        hclk1: Some(hclk),
+        hclk2: Some(hclk),
+        hclk3: Some(hclk),
+        pclk1: Some(pclk1),
+        pclk2: Some(pclk2),
+        pclk1_tim: Some(pclk1_tim),
+        pclk2_tim: Some(pclk2_tim),
+        rtc: rtc,
         pll1_q: pll.q,
-        #[cfg(all(rcc_f4, not(stm32f410)))]
-        plli2s1_q: _plli2s.q,
-        #[cfg(all(rcc_f4, not(stm32f410)))]
-        plli2s1_r: _plli2s.r,
 
-        #[cfg(any(stm32f427, stm32f429, stm32f437, stm32f439, stm32f446, stm32f469, stm32f479))]
-        pllsai1_q: _pllsai.q,
-        #[cfg(any(stm32f427, stm32f429, stm32f437, stm32f439, stm32f446, stm32f469, stm32f479))]
-        pllsai1_r: _pllsai.r,
-    });
+        #[cfg(any(stm32f2, all(stm32f4, not(stm32f410)), stm32f7))]
+        plli2s1_p: plli2s.p,
+        #[cfg(any(stm32f2, all(stm32f4, not(stm32f410)), stm32f7))]
+        plli2s1_q: plli2s.q,
+        #[cfg(any(stm32f2, all(stm32f4, not(stm32f410)), stm32f7))]
+        plli2s1_r: plli2s.r,
+
+        #[cfg(any(stm32f446, stm32f427, stm32f437, stm32f4x9, stm32f7))]
+        pllsai1_p: pllsai.p,
+        #[cfg(any(stm32f446, stm32f427, stm32f437, stm32f4x9, stm32f7))]
+        pllsai1_q: pllsai.q,
+        #[cfg(any(stm32f446, stm32f427, stm32f437, stm32f4x9, stm32f7))]
+        pllsai1_r: pllsai.r,
+
+        clk48: pll.q,
+
+        hsi_hse: None,
+        afif: None,
+    );
 }
 
 struct PllInput {
diff --git a/embassy-stm32/src/rcc/f0.rs b/embassy-stm32/src/rcc/f0.rs
index feaa2f4c0..a6b627887 100644
--- a/embassy-stm32/src/rcc/f0.rs
+++ b/embassy-stm32/src/rcc/f0.rs
@@ -1,6 +1,5 @@
 use stm32_metapac::flash::vals::Latency;
 
-use super::{set_freqs, Clocks};
 use crate::pac::rcc::vals::{Hpre, Pllmul, Pllsrc, Ppre, Sw, Usbsw};
 use crate::pac::{FLASH, RCC};
 use crate::time::Hertz;
@@ -160,13 +159,15 @@ pub(crate) unsafe fn init(config: Config) {
 
     let rtc = config.ls.init();
 
-    set_freqs(Clocks {
-        sys: Hertz(real_sysclk),
-        pclk1: Hertz(pclk),
-        pclk2: Hertz(pclk),
-        pclk1_tim: Hertz(pclk * timer_mul),
-        pclk2_tim: Hertz(pclk * timer_mul),
-        hclk1: Hertz(hclk),
-        rtc,
-    });
+    set_clocks!(
+        hsi: None,
+        lse: None,
+        sys: Some(Hertz(real_sysclk)),
+        pclk1: Some(Hertz(pclk)),
+        pclk2: Some(Hertz(pclk)),
+        pclk1_tim: Some(Hertz(pclk * timer_mul)),
+        pclk2_tim: Some(Hertz(pclk * timer_mul)),
+        hclk1: Some(Hertz(hclk)),
+        rtc: rtc,
+    );
 }
diff --git a/embassy-stm32/src/rcc/f1.rs b/embassy-stm32/src/rcc/f1.rs
index 169551e45..7f0adab27 100644
--- a/embassy-stm32/src/rcc/f1.rs
+++ b/embassy-stm32/src/rcc/f1.rs
@@ -1,6 +1,5 @@
 use core::convert::TryFrom;
 
-use super::{set_freqs, Clocks};
 use crate::pac::flash::vals::Latency;
 use crate::pac::rcc::vals::*;
 use crate::pac::{FLASH, RCC};
@@ -179,14 +178,14 @@ pub(crate) unsafe fn init(config: Config) {
 
     let rtc = config.ls.init();
 
-    set_freqs(Clocks {
-        sys: Hertz(real_sysclk),
-        pclk1: Hertz(pclk1),
-        pclk2: Hertz(pclk2),
-        pclk1_tim: Hertz(pclk1 * timer_mul1),
-        pclk2_tim: Hertz(pclk2 * timer_mul2),
-        hclk1: Hertz(hclk),
+    set_clocks!(
+        sys: Some(Hertz(real_sysclk)),
+        pclk1: Some(Hertz(pclk1)),
+        pclk2: Some(Hertz(pclk2)),
+        pclk1_tim: Some(Hertz(pclk1 * timer_mul1)),
+        pclk2_tim: Some(Hertz(pclk2 * timer_mul2)),
+        hclk1: Some(Hertz(hclk)),
         adc: Some(Hertz(adcclk)),
-        rtc,
-    });
+        rtc: rtc,
+    );
 }
diff --git a/embassy-stm32/src/rcc/f3.rs b/embassy-stm32/src/rcc/f3.rs
index bf035fd25..25866e446 100644
--- a/embassy-stm32/src/rcc/f3.rs
+++ b/embassy-stm32/src/rcc/f3.rs
@@ -4,7 +4,6 @@ use crate::pac::flash::vals::Latency;
 pub use crate::pac::rcc::vals::Adcpres;
 use crate::pac::rcc::vals::{Hpre, Pllmul, Pllsrc, Ppre, Prediv, Sw, Usbpre};
 use crate::pac::{FLASH, RCC};
-use crate::rcc::{set_freqs, Clocks};
 use crate::time::Hertz;
 
 /// HSI speed
@@ -279,13 +278,16 @@ pub(crate) unsafe fn init(config: Config) {
 
     let rtc = config.ls.init();
 
-    set_freqs(Clocks {
-        sys: sysclk,
-        pclk1: pclk1,
-        pclk2: pclk2,
-        pclk1_tim: pclk1 * timer_mul1,
-        pclk2_tim: pclk2 * timer_mul2,
-        hclk1: hclk,
+    set_clocks!(
+        hsi: None,
+        lse: None,
+        pll1_p: None,
+        sys: Some(sysclk),
+        pclk1: Some(pclk1),
+        pclk2: Some(pclk2),
+        pclk1_tim: Some(pclk1 * timer_mul1),
+        pclk2_tim: Some(pclk2 * timer_mul2),
+        hclk1: Some(hclk),
         #[cfg(rcc_f3)]
         adc: adc,
         #[cfg(all(rcc_f3, adc3_common))]
@@ -294,8 +296,8 @@ pub(crate) unsafe fn init(config: Config) {
         adc34: None,
         #[cfg(stm32f334)]
         hrtim: hrtim,
-        rtc,
-    });
+        rtc: rtc,
+    );
 }
 
 #[inline]
diff --git a/embassy-stm32/src/rcc/g0.rs b/embassy-stm32/src/rcc/g0.rs
index b38fe1dcc..e3cd46fb9 100644
--- a/embassy-stm32/src/rcc/g0.rs
+++ b/embassy-stm32/src/rcc/g0.rs
@@ -4,7 +4,6 @@ pub use crate::pac::rcc::vals::{
     Hpre as AHBPrescaler, Hsidiv as HSIPrescaler, Pllm, Plln, Pllp, Pllq, Pllr, Ppre as APBPrescaler,
 };
 use crate::pac::{FLASH, PWR, RCC};
-use crate::rcc::{set_freqs, Clocks};
 use crate::time::Hertz;
 
 /// HSI speed
@@ -352,11 +351,11 @@ pub(crate) unsafe fn init(config: Config) {
     #[cfg(not(any(stm32g0b1, stm32g0c1, stm32g0b0)))]
     let hsi48_freq: Option<Hertz> = None;
 
-    set_freqs(Clocks {
-        sys: sys_clk,
-        hclk1: ahb_freq,
-        pclk1: apb_freq,
-        pclk1_tim: apb_tim_freq,
+    set_clocks!(
+        sys: Some(sys_clk),
+        hclk1: Some(ahb_freq),
+        pclk1: Some(apb_freq),
+        pclk1_tim: Some(apb_tim_freq),
         hsi: hsi_freq,
         hsi48: hsi48_freq,
         hsi_div_8: hsi_div_8_freq,
@@ -365,6 +364,6 @@ pub(crate) unsafe fn init(config: Config) {
         lsi: lsi_freq,
         pll1_q: pll1_q_freq,
         pll1_p: pll1_p_freq,
-        rtc,
-    });
+        rtc: rtc,
+    );
 }
diff --git a/embassy-stm32/src/rcc/g4.rs b/embassy-stm32/src/rcc/g4.rs
index fca364c21..3e20bf6af 100644
--- a/embassy-stm32/src/rcc/g4.rs
+++ b/embassy-stm32/src/rcc/g4.rs
@@ -3,11 +3,10 @@ use stm32_metapac::rcc::vals::{Adcsel, Pllsrc, Sw};
 use stm32_metapac::FLASH;
 
 pub use crate::pac::rcc::vals::{
-    Adcsel as AdcClockSource, Hpre as AHBPrescaler, Pllm as PllM, Plln as PllN, Pllp as PllP, Pllq as PllQ,
-    Pllr as PllR, Ppre as APBPrescaler,
+    Adcsel as AdcClockSource, Fdcansel as FdCanClockSource, Hpre as AHBPrescaler, Pllm as PllM, Plln as PllN,
+    Pllp as PllP, Pllq as PllQ, Pllr as PllR, Ppre as APBPrescaler,
 };
 use crate::pac::{PWR, RCC};
-use crate::rcc::{set_freqs, Clocks};
 use crate::time::Hertz;
 
 /// HSI speed
@@ -87,6 +86,7 @@ pub struct Config {
     pub clock_48mhz_src: Option<Clock48MhzSrc>,
     pub adc12_clock_source: AdcClockSource,
     pub adc345_clock_source: AdcClockSource,
+    pub fdcan_clock_source: FdCanClockSource,
 
     pub ls: super::LsConfig,
 }
@@ -104,6 +104,7 @@ impl Default for Config {
             clock_48mhz_src: Some(Clock48MhzSrc::Hsi48(Default::default())),
             adc12_clock_source: Adcsel::DISABLE,
             adc345_clock_source: Adcsel::DISABLE,
+            fdcan_clock_source: FdCanClockSource::PCLK1,
             ls: Default::default(),
         }
     }
@@ -282,6 +283,7 @@ pub(crate) unsafe fn init(config: Config) {
 
     RCC.ccipr().modify(|w| w.set_adc12sel(config.adc12_clock_source));
     RCC.ccipr().modify(|w| w.set_adc345sel(config.adc345_clock_source));
+    RCC.ccipr().modify(|w| w.set_fdcansel(config.fdcan_clock_source));
 
     let adc12_ck = match config.adc12_clock_source {
         AdcClockSource::DISABLE => None,
@@ -304,20 +306,20 @@ pub(crate) unsafe fn init(config: Config) {
 
     let rtc = config.ls.init();
 
-    set_freqs(Clocks {
-        sys: sys_clk,
-        hclk1: ahb_freq,
-        hclk2: ahb_freq,
-        hclk3: ahb_freq,
-        pclk1: apb1_freq,
-        pclk1_tim: apb1_tim_freq,
-        pclk2: apb2_freq,
-        pclk2_tim: apb2_tim_freq,
+    set_clocks!(
+        sys: Some(sys_clk),
+        hclk1: Some(ahb_freq),
+        hclk2: Some(ahb_freq),
+        hclk3: Some(ahb_freq),
+        pclk1: Some(apb1_freq),
+        pclk1_tim: Some(apb1_tim_freq),
+        pclk2: Some(apb2_freq),
+        pclk2_tim: Some(apb2_tim_freq),
         adc: adc12_ck,
         adc34: adc345_ck,
         pll1_p: None,
         pll1_q: None, // TODO
         hse: None,    // TODO
-        rtc,
-    });
+        rtc: rtc,
+    );
 }
diff --git a/embassy-stm32/src/rcc/h.rs b/embassy-stm32/src/rcc/h.rs
index 15b51a398..9ac2115f0 100644
--- a/embassy-stm32/src/rcc/h.rs
+++ b/embassy-stm32/src/rcc/h.rs
@@ -7,12 +7,11 @@ pub use crate::pac::rcc::vals::Adcdacsel as AdcClockSource;
 #[cfg(stm32h7)]
 pub use crate::pac::rcc::vals::Adcsel as AdcClockSource;
 pub use crate::pac::rcc::vals::{
-    Ckpersel as PerClockSource, Hsidiv as HSIPrescaler, Plldiv as PllDiv, Pllm as PllPreDiv, Plln as PllMul,
-    Pllsrc as PllSource, Sw as Sysclk,
+    Ckpersel as PerClockSource, Fdcansel as FdCanClockSource, Hsidiv as HSIPrescaler, Plldiv as PllDiv,
+    Pllm as PllPreDiv, Plln as PllMul, Pllsrc as PllSource, Sw as Sysclk,
 };
 use crate::pac::rcc::vals::{Ckpersel, Pllrge, Pllvcosel, Timpre};
 use crate::pac::{FLASH, PWR, RCC};
-use crate::rcc::{set_freqs, Clocks};
 use crate::time::Hertz;
 
 /// HSI speed
@@ -212,6 +211,8 @@ pub struct Config {
 
     pub per_clock_source: PerClockSource,
     pub adc_clock_source: AdcClockSource,
+    pub fdcan_clock_source: FdCanClockSource,
+
     pub timer_prescaler: TimerPrescaler,
     pub voltage_scale: VoltageScale,
     pub ls: super::LsConfig,
@@ -248,6 +249,8 @@ impl Default for Config {
             #[cfg(stm32h7)]
             adc_clock_source: AdcClockSource::PER,
 
+            fdcan_clock_source: FdCanClockSource::from_bits(0), // HSE
+
             timer_prescaler: TimerPrescaler::DefaultX2,
             voltage_scale: VoltageScale::Scale0,
             ls: Default::default(),
@@ -426,7 +429,7 @@ pub(crate) unsafe fn init(config: Config) {
     };
 
     // Configure HSI48.
-    let _hsi48 = config.hsi48.map(super::init_hsi48);
+    let hsi48 = config.hsi48.map(super::init_hsi48);
 
     // Configure CSI.
     RCC.cr().modify(|w| w.set_csion(config.csi));
@@ -585,7 +588,8 @@ pub(crate) unsafe fn init(config: Config) {
 
         RCC.ccipr5().modify(|w| {
             w.set_ckpersel(config.per_clock_source);
-            w.set_adcdacsel(config.adc_clock_source)
+            w.set_adcdacsel(config.adc_clock_source);
+            w.set_fdcan12sel(config.fdcan_clock_source)
         });
     }
 
@@ -609,45 +613,33 @@ pub(crate) unsafe fn init(config: Config) {
         while !pac::SYSCFG.cccsr().read().ready() {}
     }
 
-    set_freqs(Clocks {
-        sys,
-        hclk1: hclk,
-        hclk2: hclk,
-        hclk3: hclk,
-        hclk4: hclk,
-        pclk1: apb1,
-        pclk2: apb2,
-        pclk3: apb3,
+    set_clocks!(
+        sys: Some(sys),
+        hclk1: Some(hclk),
+        hclk2: Some(hclk),
+        hclk3: Some(hclk),
+        hclk4: Some(hclk),
+        pclk1: Some(apb1),
+        pclk2: Some(apb2),
+        pclk3: Some(apb3),
         #[cfg(stm32h7)]
-        pclk4: apb4,
-        #[cfg(stm32h5)]
-        pclk4: Hertz(1),
-        pclk1_tim: apb1_tim,
-        pclk2_tim: apb2_tim,
-        adc,
-        rtc,
+        pclk4: Some(apb4),
+        pclk1_tim: Some(apb1_tim),
+        pclk2_tim: Some(apb2_tim),
+        adc: adc,
+        rtc: rtc,
 
-        #[cfg(any(stm32h5, stm32h7))]
-        hsi: None,
-        #[cfg(stm32h5)]
-        hsi48: None,
-        #[cfg(stm32h5)]
-        lsi: None,
-        #[cfg(any(stm32h5, stm32h7))]
-        csi: None,
+        hsi: hsi,
+        hsi48: hsi48,
+        csi: csi,
+        hse: hse,
 
-        #[cfg(any(stm32h5, stm32h7))]
         lse: None,
-        #[cfg(any(stm32h5, stm32h7))]
-        hse: None,
+        lsi: None,
 
-        #[cfg(any(stm32h5, stm32h7))]
         pll1_q: pll1.q,
-        #[cfg(any(stm32h5, stm32h7))]
         pll2_p: pll2.p,
-        #[cfg(any(stm32h5, stm32h7))]
         pll2_q: pll2.q,
-        #[cfg(any(stm32h5, stm32h7))]
         pll2_r: pll2.r,
         #[cfg(any(rcc_h5, stm32h7))]
         pll3_p: pll3.p,
@@ -665,12 +657,8 @@ pub(crate) unsafe fn init(config: Config) {
 
         #[cfg(stm32h5)]
         audioclk: None,
-        #[cfg(any(stm32h5, stm32h7))]
         per: None,
-
-        #[cfg(stm32h7)]
-        rcc_pclk_d3: None,
-    });
+    );
 }
 
 struct PllInput {
diff --git a/embassy-stm32/src/rcc/l.rs b/embassy-stm32/src/rcc/l.rs
index 257fd83fe..ab1681dd4 100644
--- a/embassy-stm32/src/rcc/l.rs
+++ b/embassy-stm32/src/rcc/l.rs
@@ -9,7 +9,6 @@ pub use crate::pac::rcc::vals::Clk48sel as Clk48Src;
 pub use crate::pac::rcc::vals::Hsepre as HsePrescaler;
 pub use crate::pac::rcc::vals::{Hpre as AHBPrescaler, Msirange as MSIRange, Ppre as APBPrescaler, Sw as ClockSrc};
 use crate::pac::{FLASH, RCC};
-use crate::rcc::{set_freqs, Clocks};
 use crate::time::Hertz;
 
 /// HSI speed
@@ -262,7 +261,7 @@ pub(crate) unsafe fn init(config: Config) {
     #[cfg(any(stm32l4, stm32l5, stm32wb))]
     let pllsai1 = init_pll(PllInstance::Pllsai1, config.pllsai1, &pll_input);
     #[cfg(any(stm32l47x, stm32l48x, stm32l49x, stm32l4ax, rcc_l4plus, stm32l5))]
-    let _pllsai2 = init_pll(PllInstance::Pllsai2, config.pllsai2, &pll_input);
+    let pllsai2 = init_pll(PllInstance::Pllsai2, config.pllsai2, &pll_input);
 
     let sys_clk = match config.mux {
         ClockSrc::HSE => hse.unwrap(),
@@ -274,12 +273,12 @@ pub(crate) unsafe fn init(config: Config) {
     #[cfg(any(rcc_l0_v2, stm32l4, stm32l5, stm32wb))]
     RCC.ccipr().modify(|w| w.set_clk48sel(config.clk48_src));
     #[cfg(any(rcc_l0_v2))]
-    let _clk48 = match config.clk48_src {
+    let clk48 = match config.clk48_src {
         Clk48Src::HSI48 => _hsi48,
         Clk48Src::PLL1_VCO_DIV_2 => pll.clk48,
     };
     #[cfg(any(stm32l4, stm32l5, stm32wb))]
-    let _clk48 = match config.clk48_src {
+    let clk48 = match config.clk48_src {
         Clk48Src::HSI48 => _hsi48,
         Clk48Src::MSI => msi,
         Clk48Src::PLLSAI1_Q => pllsai1.q,
@@ -376,37 +375,53 @@ pub(crate) unsafe fn init(config: Config) {
         while !RCC.extcfgr().read().c2hpref() {}
     }
 
-    set_freqs(Clocks {
-        sys: sys_clk,
-        hclk1,
+    set_clocks!(
+        sys: Some(sys_clk),
+        hclk1: Some(hclk1),
         #[cfg(any(stm32l4, stm32l5, stm32wb, stm32wl))]
-        hclk2,
+        hclk2: Some(hclk2),
         #[cfg(any(stm32l4, stm32l5, stm32wb, stm32wl))]
-        hclk3,
-        pclk1,
-        pclk2,
-        pclk1_tim,
-        pclk2_tim,
+        hclk3: Some(hclk3),
+        pclk1: Some(pclk1),
+        pclk2: Some(pclk2),
+        pclk1_tim: Some(pclk1_tim),
+        pclk2_tim: Some(pclk2_tim),
         #[cfg(stm32wl)]
-        pclk3: hclk3,
-        #[cfg(rcc_l4)]
-        hsi: None,
-        #[cfg(rcc_l4)]
-        lse: None,
-        #[cfg(rcc_l4)]
-        pllsai1_p: None,
-        #[cfg(rcc_l4)]
-        pllsai2_p: None,
-        #[cfg(rcc_l4)]
-        pll1_p: None,
-        #[cfg(rcc_l4)]
-        pll1_q: None,
-        #[cfg(rcc_l4)]
+        pclk3: Some(hclk3),
+        hsi: hsi,
+        hse: hse,
+        msi: msi,
+        #[cfg(any(rcc_l0_v2, stm32l4, stm32l5, stm32wb))]
+        clk48: clk48,
+
+        #[cfg(not(any(stm32l0, stm32l1)))]
+        pll1_p: pll.p,
+        #[cfg(not(any(stm32l0, stm32l1)))]
+        pll1_q: pll.q,
+        pll1_r: pll.r,
+
+        #[cfg(any(stm32l4, stm32l5, stm32wb))]
+        pllsai1_p: pllsai1.p,
+        #[cfg(any(stm32l4, stm32l5, stm32wb))]
+        pllsai1_q: pllsai1.q,
+        #[cfg(any(stm32l4, stm32l5, stm32wb))]
+        pllsai1_r: pllsai1.r,
+
+        #[cfg(any(stm32l47x, stm32l48x, stm32l49x, stm32l4ax, rcc_l4plus, stm32l5))]
+        pllsai2_p: pllsai2.p,
+        #[cfg(any(stm32l47x, stm32l48x, stm32l49x, stm32l4ax, rcc_l4plus, stm32l5))]
+        pllsai2_q: pllsai2.q,
+        #[cfg(any(stm32l47x, stm32l48x, stm32l49x, stm32l4ax, rcc_l4plus, stm32l5))]
+        pllsai2_r: pllsai2.r,
+
+        rtc: rtc,
+
+        // TODO
         sai1_extclk: None,
-        #[cfg(rcc_l4)]
         sai2_extclk: None,
-        rtc,
-    });
+        lsi: None,
+        lse: None,
+    );
 }
 
 #[cfg(any(stm32l0, stm32l1))]
diff --git a/embassy-stm32/src/rcc/mod.rs b/embassy-stm32/src/rcc/mod.rs
index 240ffc6d2..280da7ae3 100644
--- a/embassy-stm32/src/rcc/mod.rs
+++ b/embassy-stm32/src/rcc/mod.rs
@@ -5,8 +5,6 @@
 
 use core::mem::MaybeUninit;
 
-use crate::time::Hertz;
-
 mod bd;
 mod mco;
 pub use bd::*;
@@ -32,162 +30,7 @@ mod _version;
 
 pub use _version::*;
 
-//  Model Clock Configuration
-//
-//  pub struct Clocks {
-//      hse: Option<Hertz>,
-//      hsi: bool,
-//      lse: Option<Hertz>,
-//      lsi: bool,
-//      rtc: RtcSource,
-//  }
-
-#[derive(Clone, Copy, Debug)]
-#[cfg_attr(feature = "defmt", derive(defmt::Format))]
-pub struct Clocks {
-    pub sys: Hertz,
-
-    // APB
-    pub pclk1: Hertz,
-    pub pclk1_tim: Hertz,
-    #[cfg(not(any(rcc_c0, rcc_g0)))]
-    pub pclk2: Hertz,
-    #[cfg(not(any(rcc_c0, rcc_g0)))]
-    pub pclk2_tim: Hertz,
-    #[cfg(any(rcc_wl5, rcc_wle, rcc_h5, rcc_h50, rcc_h7, rcc_h7rm0433, rcc_h7ab, rcc_u5))]
-    pub pclk3: Hertz,
-    #[cfg(any(rcc_h7, rcc_h7rm0433, rcc_h7ab, stm32h5))]
-    pub pclk4: Hertz,
-    #[cfg(any(rcc_wba))]
-    pub pclk7: Hertz,
-
-    // AHB
-    pub hclk1: Hertz,
-    #[cfg(any(
-        rcc_l4,
-        rcc_l4plus,
-        rcc_l5,
-        rcc_f2,
-        rcc_f4,
-        rcc_f410,
-        rcc_f7,
-        rcc_h5,
-        rcc_h50,
-        rcc_h7,
-        rcc_h7rm0433,
-        rcc_h7ab,
-        rcc_g4,
-        rcc_u5,
-        rcc_wb,
-        rcc_wba,
-        rcc_wl5,
-        rcc_wle
-    ))]
-    pub hclk2: Hertz,
-    #[cfg(any(
-        rcc_l4,
-        rcc_l4plus,
-        rcc_l5,
-        rcc_f2,
-        rcc_f4,
-        rcc_f410,
-        rcc_f7,
-        rcc_h5,
-        rcc_h50,
-        rcc_h7,
-        rcc_h7rm0433,
-        rcc_h7ab,
-        rcc_u5,
-        rcc_g4,
-        rcc_wb,
-        rcc_wl5,
-        rcc_wle
-    ))]
-    pub hclk3: Hertz,
-    #[cfg(any(rcc_h5, rcc_h50, rcc_h7, rcc_h7rm0433, rcc_h7ab, rcc_wba))]
-    pub hclk4: Hertz,
-
-    #[cfg(all(rcc_f4, not(stm32f410)))]
-    pub plli2s1_q: Option<Hertz>,
-    #[cfg(all(rcc_f4, not(stm32f410)))]
-    pub plli2s1_r: Option<Hertz>,
-
-    #[cfg(rcc_l4)]
-    pub pllsai1_p: Option<Hertz>,
-    #[cfg(any(stm32f427, stm32f429, stm32f437, stm32f439, stm32f446, stm32f469, stm32f479))]
-    pub pllsai1_q: Option<Hertz>,
-    #[cfg(any(stm32f427, stm32f429, stm32f437, stm32f439, stm32f446, stm32f469, stm32f479))]
-    pub pllsai1_r: Option<Hertz>,
-    #[cfg(rcc_l4)]
-    pub pllsai2_p: Option<Hertz>,
-
-    #[cfg(any(stm32g0, stm32g4, rcc_l4))]
-    pub pll1_p: Option<Hertz>,
-    #[cfg(any(stm32h5, stm32h7, stm32f2, stm32f4, stm32f7, rcc_l4, stm32g0, stm32g4))]
-    pub pll1_q: Option<Hertz>,
-    #[cfg(any(stm32h5, stm32h7))]
-    pub pll2_p: Option<Hertz>,
-    #[cfg(any(stm32h5, stm32h7))]
-    pub pll2_q: Option<Hertz>,
-    #[cfg(any(stm32h5, stm32h7))]
-    pub pll2_r: Option<Hertz>,
-    #[cfg(any(stm32h5, stm32h7))]
-    pub pll3_p: Option<Hertz>,
-    #[cfg(any(stm32h5, stm32h7))]
-    pub pll3_q: Option<Hertz>,
-    #[cfg(any(stm32h5, stm32h7))]
-    pub pll3_r: Option<Hertz>,
-
-    #[cfg(any(
-        rcc_f1,
-        rcc_f100,
-        rcc_f1cl,
-        rcc_h5,
-        rcc_h50,
-        rcc_h7,
-        rcc_h7rm0433,
-        rcc_h7ab,
-        rcc_f3,
-        rcc_g4
-    ))]
-    pub adc: Option<Hertz>,
-
-    #[cfg(any(rcc_f3, rcc_g4))]
-    pub adc34: Option<Hertz>,
-
-    #[cfg(stm32f334)]
-    pub hrtim: Option<Hertz>,
-
-    pub rtc: Option<Hertz>,
-
-    #[cfg(any(stm32h5, stm32h7, rcc_l4, rcc_c0, stm32g0))]
-    pub hsi: Option<Hertz>,
-    #[cfg(any(stm32h5, stm32g0))]
-    pub hsi48: Option<Hertz>,
-    #[cfg(stm32g0)]
-    pub hsi_div_8: Option<Hertz>,
-    #[cfg(any(stm32g0, stm32h5))]
-    pub lsi: Option<Hertz>,
-    #[cfg(any(stm32h5, stm32h7))]
-    pub csi: Option<Hertz>,
-
-    #[cfg(any(stm32h5, stm32h7, rcc_l4, rcc_c0, stm32g0))]
-    pub lse: Option<Hertz>,
-    #[cfg(any(stm32h5, stm32h7, stm32g0, stm32g4))]
-    pub hse: Option<Hertz>,
-
-    #[cfg(stm32h5)]
-    pub audioclk: Option<Hertz>,
-    #[cfg(any(stm32h5, stm32h7))]
-    pub per: Option<Hertz>,
-
-    #[cfg(stm32h7)]
-    pub rcc_pclk_d3: Option<Hertz>,
-    #[cfg(rcc_l4)]
-    pub sai1_extclk: Option<Hertz>,
-    #[cfg(rcc_l4)]
-    pub sai2_extclk: Option<Hertz>,
-}
+pub use crate::_generated::Clocks;
 
 #[cfg(feature = "low-power")]
 /// Must be written within a critical section
diff --git a/embassy-stm32/src/rcc/u5.rs b/embassy-stm32/src/rcc/u5.rs
index dff08dc9b..9cec6c96c 100644
--- a/embassy-stm32/src/rcc/u5.rs
+++ b/embassy-stm32/src/rcc/u5.rs
@@ -1,7 +1,6 @@
 pub use crate::pac::rcc::vals::{Hpre as AHBPrescaler, Msirange, Plldiv, Pllm, Plln, Ppre as APBPrescaler};
 use crate::pac::rcc::vals::{Msirgsel, Pllmboost, Pllrge, Pllsrc, Sw};
 use crate::pac::{FLASH, PWR, RCC};
-use crate::rcc::{set_freqs, Clocks};
 use crate::time::Hertz;
 
 /// HSI speed
@@ -338,7 +337,7 @@ pub(crate) unsafe fn init(config: Config) {
         }
     };
 
-    let _hsi48 = config.hsi48.map(super::init_hsi48);
+    let hsi48 = config.hsi48.map(super::init_hsi48);
 
     // The clock source is ready
     // Calculate and set the flash wait states
@@ -448,18 +447,37 @@ pub(crate) unsafe fn init(config: Config) {
 
     let rtc = config.ls.init();
 
-    set_freqs(Clocks {
-        sys: sys_clk,
-        hclk1: ahb_freq,
-        hclk2: ahb_freq,
-        hclk3: ahb_freq,
-        pclk1: apb1_freq,
-        pclk2: apb2_freq,
-        pclk3: apb3_freq,
-        pclk1_tim: apb1_tim_freq,
-        pclk2_tim: apb2_tim_freq,
-        rtc,
-    });
+    set_clocks!(
+        sys: Some(sys_clk),
+        hclk1: Some(ahb_freq),
+        hclk2: Some(ahb_freq),
+        hclk3: Some(ahb_freq),
+        pclk1: Some(apb1_freq),
+        pclk2: Some(apb2_freq),
+        pclk3: Some(apb3_freq),
+        pclk1_tim: Some(apb1_tim_freq),
+        pclk2_tim: Some(apb2_tim_freq),
+        hsi48: hsi48,
+        rtc: rtc,
+
+        // TODO
+        hse: None,
+        hsi: None,
+        audioclk: None,
+        hsi48_div_2: None,
+        lse: None,
+        lsi: None,
+        msik: None,
+        pll1_p: None,
+        pll1_q: None,
+        pll1_r: None,
+        pll2_p: None,
+        pll2_q: None,
+        pll2_r: None,
+        pll3_p: None,
+        pll3_q: None,
+        pll3_r: None,
+    );
 }
 
 fn msirange_to_hertz(range: Msirange) -> Hertz {
diff --git a/embassy-stm32/src/rcc/wba.rs b/embassy-stm32/src/rcc/wba.rs
index c0cd91507..47ce4783c 100644
--- a/embassy-stm32/src/rcc/wba.rs
+++ b/embassy-stm32/src/rcc/wba.rs
@@ -1,88 +1,118 @@
-use stm32_metapac::rcc::vals::{Pllsrc, Sw};
-
+pub use crate::pac::pwr::vals::Vos as VoltageScale;
+use crate::pac::rcc::regs::Cfgr1;
+pub use crate::pac::rcc::vals::{
+    Adcsel as AdcClockSource, Hpre as AHBPrescaler, Hsepre as HsePrescaler, Ppre as APBPrescaler, Sw as ClockSrc,
+};
 use crate::pac::{FLASH, RCC};
-use crate::rcc::{set_freqs, Clocks};
 use crate::time::Hertz;
 
 /// HSI speed
 pub const HSI_FREQ: Hertz = Hertz(16_000_000);
+// HSE speed
+pub const HSE_FREQ: Hertz = Hertz(32_000_000);
 
-pub use crate::pac::pwr::vals::Vos as VoltageScale;
-pub use crate::pac::rcc::vals::{Hpre as AHBPrescaler, Ppre as APBPrescaler};
-
-#[derive(Copy, Clone)]
-pub enum ClockSrc {
-    HSE(Hertz),
-    HSI,
-}
-
-#[derive(Clone, Copy, Debug)]
-pub enum PllSource {
-    HSE(Hertz),
-    HSI,
-}
-
-impl Into<Pllsrc> for PllSource {
-    fn into(self) -> Pllsrc {
-        match self {
-            PllSource::HSE(..) => Pllsrc::HSE,
-            PllSource::HSI => Pllsrc::HSI,
-        }
-    }
-}
-
-impl Into<Sw> for ClockSrc {
-    fn into(self) -> Sw {
-        match self {
-            ClockSrc::HSE(..) => Sw::HSE,
-            ClockSrc::HSI => Sw::HSI,
-        }
-    }
+#[derive(Clone, Copy, Eq, PartialEq)]
+pub struct Hse {
+    pub prescaler: HsePrescaler,
 }
 
+/// Clocks configuration
 pub struct Config {
+    // base clock sources
+    pub hsi: bool,
+    pub hse: Option<Hse>,
+
+    // sysclk, buses.
     pub mux: ClockSrc,
     pub ahb_pre: AHBPrescaler,
     pub apb1_pre: APBPrescaler,
     pub apb2_pre: APBPrescaler,
     pub apb7_pre: APBPrescaler,
+
+    // low speed LSI/LSE/RTC
     pub ls: super::LsConfig,
+
+    pub adc_clock_source: AdcClockSource,
+
+    pub voltage_scale: VoltageScale,
 }
 
 impl Default for Config {
-    fn default() -> Self {
-        Self {
+    #[inline]
+    fn default() -> Config {
+        Config {
+            hse: None,
+            hsi: true,
             mux: ClockSrc::HSI,
             ahb_pre: AHBPrescaler::DIV1,
             apb1_pre: APBPrescaler::DIV1,
             apb2_pre: APBPrescaler::DIV1,
             apb7_pre: APBPrescaler::DIV1,
             ls: Default::default(),
+            adc_clock_source: AdcClockSource::HCLK1,
+            voltage_scale: VoltageScale::RANGE2,
         }
     }
 }
 
+fn hsi_enable() {
+    RCC.cr().modify(|w| w.set_hsion(true));
+    while !RCC.cr().read().hsirdy() {}
+}
+
 pub(crate) unsafe fn init(config: Config) {
+    // Switch to HSI to prevent problems with PLL configuration.
+    if !RCC.cr().read().hsion() {
+        hsi_enable()
+    }
+    if RCC.cfgr1().read().sws() != ClockSrc::HSI {
+        // Set HSI as a clock source, reset prescalers.
+        RCC.cfgr1().write_value(Cfgr1::default());
+        // Wait for clock switch status bits to change.
+        while RCC.cfgr1().read().sws() != ClockSrc::HSI {}
+    }
+
+    // Set voltage scale
+    crate::pac::PWR.vosr().write(|w| w.set_vos(config.voltage_scale));
+    while !crate::pac::PWR.vosr().read().vosrdy() {}
+
+    let rtc = config.ls.init();
+
+    let hsi = config.hsi.then(|| {
+        hsi_enable();
+
+        HSI_FREQ
+    });
+
+    let hse = config.hse.map(|hse| {
+        RCC.cr().write(|w| {
+            w.set_hseon(true);
+            w.set_hsepre(hse.prescaler);
+        });
+        while !RCC.cr().read().hserdy() {}
+
+        HSE_FREQ
+    });
+
     let sys_clk = match config.mux {
-        ClockSrc::HSE(freq) => {
-            RCC.cr().write(|w| w.set_hseon(true));
-            while !RCC.cr().read().hserdy() {}
-
-            freq
-        }
-        ClockSrc::HSI => {
-            RCC.cr().write(|w| w.set_hsion(true));
-            while !RCC.cr().read().hsirdy() {}
-
-            HSI_FREQ
-        }
+        ClockSrc::HSE => hse.unwrap(),
+        ClockSrc::HSI => hsi.unwrap(),
+        ClockSrc::_RESERVED_1 => unreachable!(),
+        ClockSrc::PLL1_R => todo!(),
     };
 
-    // TODO make configurable
-    let power_vos = VoltageScale::RANGE1;
+    assert!(sys_clk.0 <= 100_000_000);
 
-    // states and programming delay
-    let wait_states = match power_vos {
+    let hclk1 = sys_clk / config.ahb_pre;
+    let hclk2 = hclk1;
+    let hclk4 = hclk1;
+    // TODO: hclk5
+    let (pclk1, pclk1_tim) = super::util::calc_pclk(hclk1, config.apb1_pre);
+    let (pclk2, pclk2_tim) = super::util::calc_pclk(hclk1, config.apb2_pre);
+    let (pclk7, _) = super::util::calc_pclk(hclk1, config.apb7_pre);
+
+    // Set flash wait states
+    let flash_latency = match config.voltage_scale {
         VoltageScale::RANGE1 => match sys_clk.0 {
             ..=32_000_000 => 0,
             ..=64_000_000 => 1,
@@ -97,13 +127,24 @@ pub(crate) unsafe fn init(config: Config) {
         },
     };
 
-    FLASH.acr().modify(|w| {
-        w.set_latency(wait_states);
-    });
+    FLASH.acr().modify(|w| w.set_latency(flash_latency));
+    while FLASH.acr().read().latency() != flash_latency {}
+
+    // Set sram wait states
+    let _sram_latency = match config.voltage_scale {
+        VoltageScale::RANGE1 => 0,
+        VoltageScale::RANGE2 => match sys_clk.0 {
+            ..=12_000_000 => 0,
+            ..=16_000_000 => 1,
+            _ => 2,
+        },
+    };
+    // TODO: Set the SRAM wait states
 
     RCC.cfgr1().modify(|w| {
-        w.set_sw(config.mux.into());
+        w.set_sw(config.mux);
     });
+    while RCC.cfgr1().read().sws() != config.mux {}
 
     RCC.cfgr2().modify(|w| {
         w.set_hpre(config.ahb_pre);
@@ -111,45 +152,25 @@ pub(crate) unsafe fn init(config: Config) {
         w.set_ppre2(config.apb2_pre);
     });
 
-    RCC.cfgr3().modify(|w| {
-        w.set_ppre7(config.apb7_pre);
-    });
+    RCC.ccipr3().modify(|w| w.set_adcsel(config.adc_clock_source));
 
-    let ahb_freq = sys_clk / config.ahb_pre;
-    let (apb1_freq, apb1_tim_freq) = match config.apb1_pre {
-        APBPrescaler::DIV1 => (ahb_freq, ahb_freq),
-        pre => {
-            let freq = ahb_freq / pre;
-            (freq, freq * 2u32)
-        }
-    };
-    let (apb2_freq, apb2_tim_freq) = match config.apb2_pre {
-        APBPrescaler::DIV1 => (ahb_freq, ahb_freq),
-        pre => {
-            let freq = ahb_freq / pre;
-            (freq, freq * 2u32)
-        }
-    };
-    let (apb7_freq, _apb7_tim_freq) = match config.apb7_pre {
-        APBPrescaler::DIV1 => (ahb_freq, ahb_freq),
-        pre => {
-            let freq = ahb_freq / pre;
-            (freq, freq * 2u32)
-        }
-    };
+    set_clocks!(
+        sys: Some(sys_clk),
+        hclk1: Some(hclk1),
+        hclk2: Some(hclk2),
+        hclk4: Some(hclk4),
+        pclk1: Some(pclk1),
+        pclk2: Some(pclk2),
+        pclk7: Some(pclk7),
+        pclk1_tim: Some(pclk1_tim),
+        pclk2_tim: Some(pclk2_tim),
+        rtc: rtc,
+        hse: hse,
+        hsi: hsi,
 
-    let rtc = config.ls.init();
-
-    set_freqs(Clocks {
-        sys: sys_clk,
-        hclk1: ahb_freq,
-        hclk2: ahb_freq,
-        hclk4: ahb_freq,
-        pclk1: apb1_freq,
-        pclk2: apb2_freq,
-        pclk7: apb7_freq,
-        pclk1_tim: apb1_tim_freq,
-        pclk2_tim: apb2_tim_freq,
-        rtc,
-    });
+        // TODO
+        lse: None,
+        lsi: None,
+        pll1_q: None,
+    );
 }
diff --git a/embassy-stm32/src/sdmmc/mod.rs b/embassy-stm32/src/sdmmc/mod.rs
index debe26c88..61589a215 100644
--- a/embassy-stm32/src/sdmmc/mod.rs
+++ b/embassy-stm32/src/sdmmc/mod.rs
@@ -670,7 +670,7 @@ impl<'d, T: Instance, Dma: SdmmcDma<T> + 'd> Sdmmc<'d, T, Dma> {
             _ => panic!("Invalid Bus Width"),
         };
 
-        let ker_ck = T::kernel_clk();
+        let ker_ck = T::frequency();
         let (_bypass, clkdiv, new_clock) = clk_div(ker_ck, freq)?;
 
         // Enforce AHB and SDMMC_CK clock relation. See RM0433 Rev 7
@@ -1023,7 +1023,7 @@ impl<'d, T: Instance, Dma: SdmmcDma<T> + 'd> Sdmmc<'d, T, Dma> {
     /// specified frequency.
     pub async fn init_card(&mut self, freq: Hertz) -> Result<(), Error> {
         let regs = T::regs();
-        let ker_ck = T::kernel_clk();
+        let ker_ck = T::frequency();
 
         let bus_width = match self.d3.is_some() {
             true => BusWidth::Four,
@@ -1429,7 +1429,6 @@ pub(crate) mod sealed {
 
         fn regs() -> RegBlock;
         fn state() -> &'static AtomicWaker;
-        fn kernel_clk() -> Hertz;
     }
 
     pub trait Pins<T: Instance> {}
@@ -1461,61 +1460,6 @@ pub trait SdmmcDma<T: Instance> {}
 #[cfg(sdmmc_v2)]
 impl<T: Instance> SdmmcDma<T> for NoDma {}
 
-cfg_if::cfg_if! {
-    // TODO, these could not be implemented, because required clocks are not exposed in RCC:
-    // - H7 uses pll1_q_ck or pll2_r_ck depending on SDMMCSEL
-    // - L1 uses pll48
-    // - L4 uses clk48(pll48)
-    // - L4+, L5, U5 uses clk48(pll48) or PLLSAI3CLK(PLLP) depending on SDMMCSEL
-    if #[cfg(stm32f1)] {
-        // F1 uses AHB1(HCLK), which is correct in PAC
-        macro_rules! kernel_clk {
-            ($inst:ident) => {
-                <peripherals::$inst as crate::rcc::sealed::RccPeripheral>::frequency()
-            }
-        }
-    } else if #[cfg(any(stm32f2, stm32f4))] {
-        // F2, F4 always use pll48
-        macro_rules! kernel_clk {
-            ($inst:ident) => {
-                critical_section::with(|_| unsafe {
-                    unwrap!(crate::rcc::get_freqs().pll1_q)
-                })
-            }
-        }
-    } else if #[cfg(stm32f7)] {
-        macro_rules! kernel_clk {
-            (SDMMC1) => {
-                critical_section::with(|_| unsafe {
-                    let sdmmcsel = crate::pac::RCC.dckcfgr2().read().sdmmc1sel();
-                    if sdmmcsel == crate::pac::rcc::vals::Sdmmcsel::SYS {
-                        crate::rcc::get_freqs().sys
-                    } else {
-                        unwrap!(crate::rcc::get_freqs().pll1_q)
-                    }
-                })
-            };
-            (SDMMC2) => {
-                critical_section::with(|_| unsafe {
-                    let sdmmcsel = crate::pac::RCC.dckcfgr2().read().sdmmc2sel();
-                    if sdmmcsel == crate::pac::rcc::vals::Sdmmcsel::SYS {
-                        crate::rcc::get_freqs().sys
-                    } else {
-                        unwrap!(crate::rcc::get_freqs().pll1_q)
-                    }
-                })
-            };
-        }
-    } else {
-        // Use default peripheral clock and hope it works
-        macro_rules! kernel_clk {
-            ($inst:ident) => {
-                <peripherals::$inst as crate::rcc::sealed::RccPeripheral>::frequency()
-            }
-        }
-    }
-}
-
 foreach_peripheral!(
     (sdmmc, $inst:ident) => {
         impl sealed::Instance for peripherals::$inst {
@@ -1529,10 +1473,6 @@ foreach_peripheral!(
                 static WAKER: ::embassy_sync::waitqueue::AtomicWaker = ::embassy_sync::waitqueue::AtomicWaker::new();
                 &WAKER
             }
-
-            fn kernel_clk() -> Hertz {
-                kernel_clk!($inst)
-            }
         }
 
         impl Instance for peripherals::$inst {}
diff --git a/embassy-stm32/src/timer/complementary_pwm.rs b/embassy-stm32/src/timer/complementary_pwm.rs
index 71d7110b5..eddce0404 100644
--- a/embassy-stm32/src/timer/complementary_pwm.rs
+++ b/embassy-stm32/src/timer/complementary_pwm.rs
@@ -54,6 +54,7 @@ pub struct ComplementaryPwm<'d, T> {
 
 impl<'d, T: ComplementaryCaptureCompare16bitInstance> ComplementaryPwm<'d, T> {
     /// Create a new complementary PWM driver.
+    #[allow(clippy::too_many_arguments)]
     pub fn new(
         tim: impl Peripheral<P = T> + 'd,
         _ch1: Option<PwmPin<'d, T, Ch1>>,
@@ -165,7 +166,7 @@ impl<'d, T: ComplementaryCaptureCompare16bitInstance> embedded_hal_02::Pwm for C
     }
 
     fn get_period(&self) -> Self::Time {
-        self.inner.get_frequency().into()
+        self.inner.get_frequency()
     }
 
     fn get_duty(&self, channel: Self::Channel) -> Self::Duty {
diff --git a/embassy-stm32/src/timer/mod.rs b/embassy-stm32/src/timer/mod.rs
index d07fd2776..210bf7153 100644
--- a/embassy-stm32/src/timer/mod.rs
+++ b/embassy-stm32/src/timer/mod.rs
@@ -311,6 +311,26 @@ pub(crate) mod sealed {
                 .ccmr_output(channel_index / 2)
                 .modify(|w| w.set_ocpe(channel_index % 2, preload));
         }
+
+        /// Get capture compare DMA selection
+        fn get_cc_dma_selection(&self) -> super::vals::Ccds {
+            Self::regs_gp16().cr2().read().ccds()
+        }
+
+        /// Set capture compare DMA selection
+        fn set_cc_dma_selection(&mut self, ccds: super::vals::Ccds) {
+            Self::regs_gp16().cr2().modify(|w| w.set_ccds(ccds))
+        }
+
+        /// Get capture compare DMA enable state
+        fn get_cc_dma_enable_state(&self, channel: Channel) -> bool {
+            Self::regs_gp16().dier().read().ccde(channel.index())
+        }
+
+        /// Set capture compare DMA enable state
+        fn set_cc_dma_enable_state(&mut self, channel: Channel, ccde: bool) {
+            Self::regs_gp16().dier().modify(|w| w.set_ccde(channel.index(), ccde))
+        }
     }
 
     /// Capture/Compare 16-bit timer instance with complementary pin support.
@@ -450,20 +470,17 @@ pub enum CountingMode {
 impl CountingMode {
     /// Return whether this mode is edge-aligned (up or down).
     pub fn is_edge_aligned(&self) -> bool {
-        match self {
-            CountingMode::EdgeAlignedUp | CountingMode::EdgeAlignedDown => true,
-            _ => false,
-        }
+        matches!(self, CountingMode::EdgeAlignedUp | CountingMode::EdgeAlignedDown)
     }
 
     /// Return whether this mode is center-aligned.
     pub fn is_center_aligned(&self) -> bool {
-        match self {
+        matches!(
+            self,
             CountingMode::CenterAlignedDownInterrupts
-            | CountingMode::CenterAlignedUpInterrupts
-            | CountingMode::CenterAlignedBothInterrupts => true,
-            _ => false,
-        }
+                | CountingMode::CenterAlignedUpInterrupts
+                | CountingMode::CenterAlignedBothInterrupts
+        )
     }
 }
 
@@ -705,3 +722,8 @@ foreach_interrupt! {
 
 // Update Event trigger DMA for every timer
 dma_trait!(UpDma, Basic16bitInstance);
+
+dma_trait!(Ch1Dma, CaptureCompare16bitInstance);
+dma_trait!(Ch2Dma, CaptureCompare16bitInstance);
+dma_trait!(Ch3Dma, CaptureCompare16bitInstance);
+dma_trait!(Ch4Dma, CaptureCompare16bitInstance);
diff --git a/embassy-stm32/src/timer/simple_pwm.rs b/embassy-stm32/src/timer/simple_pwm.rs
index 83a3e9291..0b4c1225f 100644
--- a/embassy-stm32/src/timer/simple_pwm.rs
+++ b/embassy-stm32/src/timer/simple_pwm.rs
@@ -160,7 +160,7 @@ impl<'d, T: CaptureCompare16bitInstance> SimplePwm<'d, T> {
     ///
     /// Note:  
     /// you will need to provide corresponding TIMx_UP DMA channel to use this method.
-    pub async fn gen_waveform(
+    pub async fn waveform_up(
         &mut self,
         dma: impl Peripheral<P = impl super::UpDma<T>>,
         channel: Channel,
@@ -226,6 +226,95 @@ impl<'d, T: CaptureCompare16bitInstance> SimplePwm<'d, T> {
     }
 }
 
+macro_rules! impl_waveform_chx {
+    ($fn_name:ident, $dma_ch:ident, $cc_ch:ident) => {
+        impl<'d, T: CaptureCompare16bitInstance> SimplePwm<'d, T> {
+            /// Generate a sequence of PWM waveform
+            ///
+            /// Note:
+            /// you will need to provide corresponding TIMx_CHy DMA channel to use this method.
+            pub async fn $fn_name(&mut self, dma: impl Peripheral<P = impl super::$dma_ch<T>>, duty: &[u16]) {
+                use super::vals::Ccds;
+
+                assert!(duty.iter().all(|v| *v <= self.get_max_duty()));
+
+                into_ref!(dma);
+
+                #[allow(clippy::let_unit_value)] // eg. stm32f334
+                let req = dma.request();
+
+                let cc_channel = super::Channel::$cc_ch;
+
+                let original_duty_state = self.get_duty(cc_channel);
+                let original_enable_state = self.is_enabled(cc_channel);
+                let original_cc_dma_on_update = self.inner.get_cc_dma_selection() == Ccds::ONUPDATE;
+                let original_cc_dma_enabled = self.inner.get_cc_dma_enable_state(cc_channel);
+
+                // redirect CC DMA request onto Update Event
+                if !original_cc_dma_on_update {
+                    self.inner.set_cc_dma_selection(Ccds::ONUPDATE)
+                }
+
+                if !original_cc_dma_enabled {
+                    self.inner.set_cc_dma_enable_state(cc_channel, true);
+                }
+
+                if !original_enable_state {
+                    self.enable(cc_channel);
+                }
+
+                unsafe {
+                    #[cfg(not(any(bdma, gpdma)))]
+                    use crate::dma::{Burst, FifoThreshold};
+                    use crate::dma::{Transfer, TransferOptions};
+
+                    let dma_transfer_option = TransferOptions {
+                        #[cfg(not(any(bdma, gpdma)))]
+                        fifo_threshold: Some(FifoThreshold::Full),
+                        #[cfg(not(any(bdma, gpdma)))]
+                        mburst: Burst::Incr8,
+                        ..Default::default()
+                    };
+
+                    Transfer::new_write(
+                        &mut dma,
+                        req,
+                        duty,
+                        T::regs_gp16().ccr(cc_channel.index()).as_ptr() as *mut _,
+                        dma_transfer_option,
+                    )
+                    .await
+                };
+
+                // restore output compare state
+                if !original_enable_state {
+                    self.disable(cc_channel);
+                }
+
+                self.set_duty(cc_channel, original_duty_state);
+
+                // Since DMA is closed before timer Capture Compare Event trigger DMA is turn off,
+                // this can almost always trigger a DMA FIFO error.
+                //
+                // optional TODO:
+                // clean FEIF after disable UDE
+                if !original_cc_dma_enabled {
+                    self.inner.set_cc_dma_enable_state(cc_channel, false);
+                }
+
+                if !original_cc_dma_on_update {
+                    self.inner.set_cc_dma_selection(Ccds::ONCOMPARE)
+                }
+            }
+        }
+    };
+}
+
+impl_waveform_chx!(waveform_ch1, Ch1Dma, Ch1);
+impl_waveform_chx!(waveform_ch2, Ch2Dma, Ch2);
+impl_waveform_chx!(waveform_ch3, Ch3Dma, Ch3);
+impl_waveform_chx!(waveform_ch4, Ch4Dma, Ch4);
+
 impl<'d, T: CaptureCompare16bitInstance> embedded_hal_02::Pwm for SimplePwm<'d, T> {
     type Channel = Channel;
     type Time = Hertz;
@@ -240,7 +329,7 @@ impl<'d, T: CaptureCompare16bitInstance> embedded_hal_02::Pwm for SimplePwm<'d,
     }
 
     fn get_period(&self) -> Self::Time {
-        self.inner.get_frequency().into()
+        self.inner.get_frequency()
     }
 
     fn get_duty(&self, channel: Self::Channel) -> Self::Duty {
diff --git a/embassy-stm32/src/usb/usb.rs b/embassy-stm32/src/usb/usb.rs
index f39915906..34d6b52fd 100644
--- a/embassy-stm32/src/usb/usb.rs
+++ b/embassy-stm32/src/usb/usb.rs
@@ -280,7 +280,7 @@ impl<'d, T: Instance> Driver<'d, T> {
         #[cfg(time)]
         embassy_time::block_for(embassy_time::Duration::from_millis(100));
         #[cfg(not(time))]
-        cortex_m::asm::delay(unsafe { crate::rcc::get_freqs() }.sys.0 / 10);
+        cortex_m::asm::delay(unsafe { crate::rcc::get_freqs() }.sys.unwrap().0 / 10);
 
         #[cfg(not(usb_v4))]
         regs.btable().write(|w| w.set_btable(0));
diff --git a/embassy-sync/src/priority_channel.rs b/embassy-sync/src/priority_channel.rs
index bd75c0135..e77678c24 100644
--- a/embassy-sync/src/priority_channel.rs
+++ b/embassy-sync/src/priority_channel.rs
@@ -325,7 +325,7 @@ where
 ///
 /// Sent data may be reordered based on their priorty within the channel.
 /// For example, in a [`Max`](heapless::binary_heap::Max) [`PriorityChannel`]
-/// containing `u32`'s, data sent in the following order `[1, 2, 3]` will be recieved as `[3, 2, 1]`.
+/// containing `u32`'s, data sent in the following order `[1, 2, 3]` will be received as `[3, 2, 1]`.
 pub struct PriorityChannel<M, T, K, const N: usize>
 where
     T: Ord,
diff --git a/embassy-sync/src/ring_buffer.rs b/embassy-sync/src/ring_buffer.rs
index d95ffa7c9..81e60c42b 100644
--- a/embassy-sync/src/ring_buffer.rs
+++ b/embassy-sync/src/ring_buffer.rs
@@ -3,7 +3,7 @@ use core::ops::Range;
 pub struct RingBuffer<const N: usize> {
     start: usize,
     end: usize,
-    empty: bool,
+    full: bool,
 }
 
 impl<const N: usize> RingBuffer<N> {
@@ -11,13 +11,13 @@ impl<const N: usize> RingBuffer<N> {
         Self {
             start: 0,
             end: 0,
-            empty: true,
+            full: false,
         }
     }
 
     pub fn push_buf(&mut self) -> Range<usize> {
-        if self.start == self.end && !self.empty {
-            trace!("  ringbuf: push_buf empty");
+        if self.is_full() {
+            trace!("  ringbuf: push_buf full");
             return 0..0;
         }
 
@@ -38,11 +38,11 @@ impl<const N: usize> RingBuffer<N> {
         }
 
         self.end = self.wrap(self.end + n);
-        self.empty = false;
+        self.full = self.start == self.end;
     }
 
     pub fn pop_buf(&mut self) -> Range<usize> {
-        if self.empty {
+        if self.is_empty() {
             trace!("  ringbuf: pop_buf empty");
             return 0..0;
         }
@@ -64,20 +64,20 @@ impl<const N: usize> RingBuffer<N> {
         }
 
         self.start = self.wrap(self.start + n);
-        self.empty = self.start == self.end;
+        self.full = false;
     }
 
     pub fn is_full(&self) -> bool {
-        self.start == self.end && !self.empty
+        self.full
     }
 
     pub fn is_empty(&self) -> bool {
-        self.empty
+        self.start == self.end && !self.full
     }
 
     #[allow(unused)]
     pub fn len(&self) -> usize {
-        if self.empty {
+        if self.is_empty() {
             0
         } else if self.start < self.end {
             self.end - self.start
@@ -89,7 +89,7 @@ impl<const N: usize> RingBuffer<N> {
     pub fn clear(&mut self) {
         self.start = 0;
         self.end = 0;
-        self.empty = true;
+        self.full = false;
     }
 
     fn wrap(&self, n: usize) -> usize {
diff --git a/embassy-time/src/lib.rs b/embassy-time/src/lib.rs
index d27eb92f6..3c8575ee9 100644
--- a/embassy-time/src/lib.rs
+++ b/embassy-time/src/lib.rs
@@ -32,7 +32,7 @@ pub use delay::{block_for, Delay};
 pub use duration::Duration;
 pub use embassy_time_driver::TICK_HZ;
 pub use instant::Instant;
-pub use timer::{with_timeout, Ticker, TimeoutError, Timer};
+pub use timer::{with_deadline, with_timeout, Ticker, TimeoutError, Timer};
 
 const fn gcd(a: u64, b: u64) -> u64 {
     if b == 0 {
diff --git a/embassy-time/src/timer.rs b/embassy-time/src/timer.rs
index 565a65cb8..daa4c1699 100644
--- a/embassy-time/src/timer.rs
+++ b/embassy-time/src/timer.rs
@@ -8,7 +8,7 @@ use futures_util::{pin_mut, Stream};
 
 use crate::{Duration, Instant};
 
-/// Error returned by [`with_timeout`] on timeout.
+/// Error returned by [`with_timeout`] and [`with_deadline`] on timeout.
 #[derive(Debug, Clone, PartialEq, Eq)]
 #[cfg_attr(feature = "defmt", derive(defmt::Format))]
 pub struct TimeoutError;
@@ -26,6 +26,19 @@ pub async fn with_timeout<F: Future>(timeout: Duration, fut: F) -> Result<F::Out
     }
 }
 
+/// Runs a given future with a deadline time.
+///
+/// If the future completes before the deadline, its output is returned. Otherwise, on timeout,
+/// work on the future is stopped (`poll` is no longer called), the future is dropped and `Err(TimeoutError)` is returned.
+pub async fn with_deadline<F: Future>(at: Instant, fut: F) -> Result<F::Output, TimeoutError> {
+    let timeout_fut = Timer::at(at);
+    pin_mut!(fut);
+    match select(fut, timeout_fut).await {
+        Either::Left((r, _)) => Ok(r),
+        Either::Right(_) => Err(TimeoutError),
+    }
+}
+
 /// A future that completes at a specified [Instant](struct.Instant.html).
 #[must_use = "futures do nothing unless you `.await` or poll them"]
 pub struct Timer {
diff --git a/examples/nrf51/.cargo/config.toml b/examples/nrf51/.cargo/config.toml
new file mode 100644
index 000000000..1671f5db1
--- /dev/null
+++ b/examples/nrf51/.cargo/config.toml
@@ -0,0 +1,9 @@
+[target.'cfg(all(target_arch = "arm", target_os = "none"))']
+# replace nRF51422_xxAA with your chip as listed in `probe-rs chip list`
+runner = "probe-rs run --chip nRF51422_xxAA"
+
+[build]
+target = "thumbv6m-none-eabi"
+
+[env]
+DEFMT_LOG = "trace"
diff --git a/examples/nrf51/Cargo.toml b/examples/nrf51/Cargo.toml
new file mode 100644
index 000000000..d1e919a33
--- /dev/null
+++ b/examples/nrf51/Cargo.toml
@@ -0,0 +1,20 @@
+[package]
+edition = "2021"
+name = "embassy-nrf51-examples"
+version = "0.1.0"
+license = "MIT OR Apache-2.0"
+
+[dependencies]
+embassy-executor = { version = "0.5.0", path = "../../embassy-executor", features = ["task-arena-size-4096", "arch-cortex-m", "executor-thread", "executor-interrupt", "defmt", "integrated-timers"] }
+embassy-time = { version = "0.3.0", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime"] }
+embassy-nrf = { version = "0.1.0", path = "../../embassy-nrf", features = ["defmt", "nrf51", "time-driver-rtc1", "unstable-pac", "time", "rt"] }
+
+defmt = "0.3"
+defmt-rtt = "0.4"
+
+cortex-m = { version = "0.7.6", features = ["inline-asm", "critical-section-single-core"] }
+cortex-m-rt = "0.7"
+panic-probe = { version = "0.3", features = ["print-defmt"] }
+
+[profile.release]
+debug = 2
diff --git a/examples/nrf51/build.rs b/examples/nrf51/build.rs
new file mode 100644
index 000000000..30691aa97
--- /dev/null
+++ b/examples/nrf51/build.rs
@@ -0,0 +1,35 @@
+//! This build script copies the `memory.x` file from the crate root into
+//! a directory where the linker can always find it at build time.
+//! For many projects this is optional, as the linker always searches the
+//! project root directory -- wherever `Cargo.toml` is. However, if you
+//! are using a workspace or have a more complicated build setup, this
+//! build script becomes required. Additionally, by requesting that
+//! Cargo re-run the build script whenever `memory.x` is changed,
+//! updating `memory.x` ensures a rebuild of the application with the
+//! new memory settings.
+
+use std::env;
+use std::fs::File;
+use std::io::Write;
+use std::path::PathBuf;
+
+fn main() {
+    // Put `memory.x` in our output directory and ensure it's
+    // on the linker search path.
+    let out = &PathBuf::from(env::var_os("OUT_DIR").unwrap());
+    File::create(out.join("memory.x"))
+        .unwrap()
+        .write_all(include_bytes!("memory.x"))
+        .unwrap();
+    println!("cargo:rustc-link-search={}", out.display());
+
+    // By default, Cargo will re-run a build script whenever
+    // any file in the project changes. By specifying `memory.x`
+    // here, we ensure the build script is only re-run when
+    // `memory.x` is changed.
+    println!("cargo:rerun-if-changed=memory.x");
+
+    println!("cargo:rustc-link-arg-bins=--nmagic");
+    println!("cargo:rustc-link-arg-bins=-Tlink.x");
+    println!("cargo:rustc-link-arg-bins=-Tdefmt.x");
+}
diff --git a/examples/nrf51/memory.x b/examples/nrf51/memory.x
new file mode 100644
index 000000000..98b3c792f
--- /dev/null
+++ b/examples/nrf51/memory.x
@@ -0,0 +1,5 @@
+MEMORY
+{
+  FLASH                    : ORIGIN = 0x00000000, LENGTH = 128K
+  RAM                      : ORIGIN = 0x20000000, LENGTH = 16K
+}
diff --git a/examples/nrf51/src/bin/blinky.rs b/examples/nrf51/src/bin/blinky.rs
new file mode 100644
index 000000000..7c12ffcbc
--- /dev/null
+++ b/examples/nrf51/src/bin/blinky.rs
@@ -0,0 +1,20 @@
+#![no_std]
+#![no_main]
+
+use embassy_executor::Spawner;
+use embassy_nrf::gpio::{Level, Output, OutputDrive};
+use embassy_time::Timer;
+use {defmt_rtt as _, panic_probe as _};
+
+#[embassy_executor::main]
+async fn main(_spawner: Spawner) {
+    let p = embassy_nrf::init(Default::default());
+    let mut led = Output::new(p.P0_21, Level::Low, OutputDrive::Standard);
+
+    loop {
+        led.set_high();
+        Timer::after_millis(300).await;
+        led.set_low();
+        Timer::after_millis(300).await;
+    }
+}
diff --git a/examples/rp/src/bin/debounce.rs b/examples/rp/src/bin/debounce.rs
new file mode 100644
index 000000000..0077f19fc
--- /dev/null
+++ b/examples/rp/src/bin/debounce.rs
@@ -0,0 +1,80 @@
+//! This example shows the ease of debouncing a button with async rust.
+//! Hook up a button or switch between pin 9 and ground.
+
+#![no_std]
+#![no_main]
+
+use defmt::info;
+use embassy_executor::Spawner;
+use embassy_rp::gpio::{Input, Level, Pull};
+use embassy_time::{with_deadline, Duration, Instant, Timer};
+use {defmt_rtt as _, panic_probe as _};
+
+pub struct Debouncer<'a> {
+    input: Input<'a>,
+    debounce: Duration,
+}
+
+impl<'a> Debouncer<'a> {
+    pub fn new(input: Input<'a>, debounce: Duration) -> Self {
+        Self { input, debounce }
+    }
+
+    pub async fn debounce(&mut self) -> Level {
+        loop {
+            let l1 = self.input.get_level();
+
+            self.input.wait_for_any_edge().await;
+
+            Timer::after(self.debounce).await;
+
+            let l2 = self.input.get_level();
+            if l1 != l2 {
+                break l2;
+            }
+        }
+    }
+}
+
+#[embassy_executor::main]
+async fn main(_spawner: Spawner) {
+    let p = embassy_rp::init(Default::default());
+    let mut btn = Debouncer::new(Input::new(p.PIN_9, Pull::Up), Duration::from_millis(20));
+
+    info!("Debounce Demo");
+
+    loop {
+        // button pressed
+        btn.debounce().await;
+        let start = Instant::now();
+        info!("Button Press");
+
+        match with_deadline(start + Duration::from_secs(1), btn.debounce()).await {
+            // Button Released < 1s
+            Ok(_) => {
+                info!("Button pressed for: {}ms", start.elapsed().as_millis());
+                continue;
+            }
+            // button held for > 1s
+            Err(_) => {
+                info!("Button Held");
+            }
+        }
+
+        match with_deadline(start + Duration::from_secs(5), btn.debounce()).await {
+            // Button released <5s
+            Ok(_) => {
+                info!("Button pressed for: {}ms", start.elapsed().as_millis());
+                continue;
+            }
+            // button held for > >5s
+            Err(_) => {
+                info!("Button Long Held");
+            }
+        }
+
+        // wait for button release before handling another press
+        btn.debounce().await;
+        info!("Button pressed for: {}ms", start.elapsed().as_millis());
+    }
+}
diff --git a/examples/rp/src/bin/i2c_slave.rs b/examples/rp/src/bin/i2c_slave.rs
index 479f9a16a..ac470d2be 100644
--- a/examples/rp/src/bin/i2c_slave.rs
+++ b/examples/rp/src/bin/i2c_slave.rs
@@ -26,7 +26,7 @@ async fn device_task(mut dev: i2c_slave::I2cSlave<'static, I2C1>) -> ! {
     loop {
         let mut buf = [0u8; 128];
         match dev.listen(&mut buf).await {
-            Ok(i2c_slave::Command::GeneralCall(len)) => info!("Device recieved general call write: {}", buf[..len]),
+            Ok(i2c_slave::Command::GeneralCall(len)) => info!("Device received general call write: {}", buf[..len]),
             Ok(i2c_slave::Command::Read) => loop {
                 match dev.respond_to_read(&[state]).await {
                     Ok(x) => match x {
@@ -40,9 +40,9 @@ async fn device_task(mut dev: i2c_slave::I2cSlave<'static, I2C1>) -> ! {
                     Err(e) => error!("error while responding {}", e),
                 }
             },
-            Ok(i2c_slave::Command::Write(len)) => info!("Device recieved write: {}", buf[..len]),
+            Ok(i2c_slave::Command::Write(len)) => info!("Device received write: {}", buf[..len]),
             Ok(i2c_slave::Command::WriteRead(len)) => {
-                info!("device recieved write read: {:x}", buf[..len]);
+                info!("device received write read: {:x}", buf[..len]);
                 match buf[0] {
                     // Set the state
                     0xC2 => {
diff --git a/examples/stm32f4/src/bin/ws2812_pwm.rs b/examples/stm32f4/src/bin/ws2812_pwm.rs
index 239709253..6122cea2d 100644
--- a/examples/stm32f4/src/bin/ws2812_pwm.rs
+++ b/examples/stm32f4/src/bin/ws2812_pwm.rs
@@ -91,7 +91,7 @@ async fn main(_spawner: Spawner) {
     loop {
         for &color in color_list {
             // with &mut, we can easily reuse same DMA channel multiple times
-            ws2812_pwm.gen_waveform(&mut dp.DMA1_CH2, pwm_channel, color).await;
+            ws2812_pwm.waveform_up(&mut dp.DMA1_CH2, pwm_channel, color).await;
             // ws2812 need at least 50 us low level input to confirm the input data and change it's state
             Timer::after_micros(50).await;
             // wait until ticker tick
diff --git a/examples/stm32g4/src/bin/can.rs b/examples/stm32g4/src/bin/can.rs
new file mode 100644
index 000000000..727921fba
--- /dev/null
+++ b/examples/stm32g4/src/bin/can.rs
@@ -0,0 +1,56 @@
+#![no_std]
+#![no_main]
+use defmt::*;
+use embassy_executor::Spawner;
+use embassy_stm32::peripherals::*;
+use embassy_stm32::{bind_interrupts, can, Config};
+use embassy_time::Timer;
+use {defmt_rtt as _, panic_probe as _};
+
+bind_interrupts!(struct Irqs {
+    FDCAN1_IT0 => can::IT0InterruptHandler<FDCAN1>;
+    FDCAN1_IT1 => can::IT1InterruptHandler<FDCAN1>;
+});
+
+#[embassy_executor::main]
+async fn main(_spawner: Spawner) {
+    let config = Config::default();
+
+    let peripherals = embassy_stm32::init(config);
+
+    let mut can = can::Fdcan::new(peripherals.FDCAN1, peripherals.PA11, peripherals.PA12, Irqs);
+
+    // 250k bps
+    can.set_bitrate(250_000);
+
+    info!("Configured");
+
+    //let mut can = can.into_external_loopback_mode();
+    let mut can = can.into_normal_mode();
+
+    let mut i = 0;
+    loop {
+        let frame = can::TxFrame::new(
+            can::TxFrameHeader {
+                len: 1,
+                frame_format: can::FrameFormat::Standard,
+                id: can::StandardId::new(0x123).unwrap().into(),
+                bit_rate_switching: false,
+                marker: None,
+            },
+            &[i],
+        )
+        .unwrap();
+        info!("Writing frame");
+        _ = can.write(&frame).await;
+
+        match can.read().await {
+            Ok(rx_frame) => info!("Rx: {}", rx_frame.data()[0]),
+            Err(_err) => error!("Error in frame"),
+        }
+
+        Timer::after_millis(250).await;
+
+        i += 1;
+    }
+}
diff --git a/examples/stm32h5/src/bin/can.rs b/examples/stm32h5/src/bin/can.rs
new file mode 100644
index 000000000..2906d1576
--- /dev/null
+++ b/examples/stm32h5/src/bin/can.rs
@@ -0,0 +1,74 @@
+#![no_std]
+#![no_main]
+
+use defmt::*;
+use embassy_executor::Spawner;
+use embassy_stm32::peripherals::*;
+use embassy_stm32::{bind_interrupts, can, rcc, Config};
+use embassy_time::Timer;
+use {defmt_rtt as _, panic_probe as _};
+
+bind_interrupts!(struct Irqs {
+    FDCAN1_IT0 => can::IT0InterruptHandler<FDCAN1>;
+    FDCAN1_IT1 => can::IT1InterruptHandler<FDCAN1>;
+});
+
+#[embassy_executor::main]
+async fn main(_spawner: Spawner) {
+    let mut config = Config::default();
+
+    // configure FDCAN to use PLL1_Q at 64 MHz
+    config.rcc.pll1 = Some(rcc::Pll {
+        source: rcc::PllSource::HSI,
+        prediv: rcc::PllPreDiv::DIV4,
+        mul: rcc::PllMul::MUL8,
+        divp: None,
+        divq: Some(rcc::PllDiv::DIV2),
+        divr: None,
+    });
+    config.rcc.fdcan_clock_source = rcc::FdCanClockSource::PLL1_Q;
+
+    let peripherals = embassy_stm32::init(config);
+
+    let mut can = can::Fdcan::new(peripherals.FDCAN1, peripherals.PA11, peripherals.PA12, Irqs);
+
+    can.can.apply_config(
+        can::config::FdCanConfig::default().set_nominal_bit_timing(can::config::NominalBitTiming {
+            sync_jump_width: 1.try_into().unwrap(),
+            prescaler: 8.try_into().unwrap(),
+            seg1: 13.try_into().unwrap(),
+            seg2: 2.try_into().unwrap(),
+        }),
+    );
+
+    info!("Configured");
+
+    let mut can = can.into_external_loopback_mode();
+    //let mut can = can.into_normal_mode();
+
+    let mut i = 0;
+    loop {
+        let frame = can::TxFrame::new(
+            can::TxFrameHeader {
+                len: 1,
+                frame_format: can::FrameFormat::Standard,
+                id: can::StandardId::new(0x123).unwrap().into(),
+                bit_rate_switching: false,
+                marker: None,
+            },
+            &[i],
+        )
+        .unwrap();
+        info!("Writing frame");
+        _ = can.write(&frame).await;
+
+        match can.read().await {
+            Ok(rx_frame) => info!("Rx: {}", rx_frame.data()[0]),
+            Err(_err) => error!("Error in frame"),
+        }
+
+        Timer::after_millis(250).await;
+
+        i += 1;
+    }
+}
diff --git a/examples/stm32h7/src/bin/can.rs b/examples/stm32h7/src/bin/can.rs
new file mode 100644
index 000000000..2906d1576
--- /dev/null
+++ b/examples/stm32h7/src/bin/can.rs
@@ -0,0 +1,74 @@
+#![no_std]
+#![no_main]
+
+use defmt::*;
+use embassy_executor::Spawner;
+use embassy_stm32::peripherals::*;
+use embassy_stm32::{bind_interrupts, can, rcc, Config};
+use embassy_time::Timer;
+use {defmt_rtt as _, panic_probe as _};
+
+bind_interrupts!(struct Irqs {
+    FDCAN1_IT0 => can::IT0InterruptHandler<FDCAN1>;
+    FDCAN1_IT1 => can::IT1InterruptHandler<FDCAN1>;
+});
+
+#[embassy_executor::main]
+async fn main(_spawner: Spawner) {
+    let mut config = Config::default();
+
+    // configure FDCAN to use PLL1_Q at 64 MHz
+    config.rcc.pll1 = Some(rcc::Pll {
+        source: rcc::PllSource::HSI,
+        prediv: rcc::PllPreDiv::DIV4,
+        mul: rcc::PllMul::MUL8,
+        divp: None,
+        divq: Some(rcc::PllDiv::DIV2),
+        divr: None,
+    });
+    config.rcc.fdcan_clock_source = rcc::FdCanClockSource::PLL1_Q;
+
+    let peripherals = embassy_stm32::init(config);
+
+    let mut can = can::Fdcan::new(peripherals.FDCAN1, peripherals.PA11, peripherals.PA12, Irqs);
+
+    can.can.apply_config(
+        can::config::FdCanConfig::default().set_nominal_bit_timing(can::config::NominalBitTiming {
+            sync_jump_width: 1.try_into().unwrap(),
+            prescaler: 8.try_into().unwrap(),
+            seg1: 13.try_into().unwrap(),
+            seg2: 2.try_into().unwrap(),
+        }),
+    );
+
+    info!("Configured");
+
+    let mut can = can.into_external_loopback_mode();
+    //let mut can = can.into_normal_mode();
+
+    let mut i = 0;
+    loop {
+        let frame = can::TxFrame::new(
+            can::TxFrameHeader {
+                len: 1,
+                frame_format: can::FrameFormat::Standard,
+                id: can::StandardId::new(0x123).unwrap().into(),
+                bit_rate_switching: false,
+                marker: None,
+            },
+            &[i],
+        )
+        .unwrap();
+        info!("Writing frame");
+        _ = can.write(&frame).await;
+
+        match can.read().await {
+            Ok(rx_frame) => info!("Rx: {}", rx_frame.data()[0]),
+            Err(_err) => error!("Error in frame"),
+        }
+
+        Timer::after_millis(250).await;
+
+        i += 1;
+    }
+}
diff --git a/examples/stm32h7/src/bin/eth_client.rs b/examples/stm32h7/src/bin/eth_client.rs
index dcc6e36e2..aeb169e19 100644
--- a/examples/stm32h7/src/bin/eth_client.rs
+++ b/examples/stm32h7/src/bin/eth_client.rs
@@ -65,6 +65,7 @@ async fn main(spawner: Spawner) -> ! {
     let mac_addr = [0x00, 0x00, 0xDE, 0xAD, 0xBE, 0xEF];
 
     static PACKETS: StaticCell<PacketQueue<16, 16>> = StaticCell::new();
+
     let device = Ethernet::new(
         PACKETS.init(PacketQueue::<16, 16>::new()),
         p.ETH,
diff --git a/examples/stm32h7/src/bin/eth_client_mii.rs b/examples/stm32h7/src/bin/eth_client_mii.rs
new file mode 100644
index 000000000..de6ea522a
--- /dev/null
+++ b/examples/stm32h7/src/bin/eth_client_mii.rs
@@ -0,0 +1,142 @@
+#![no_std]
+#![no_main]
+
+use defmt::*;
+use embassy_executor::Spawner;
+use embassy_net::tcp::client::{TcpClient, TcpClientState};
+use embassy_net::{Stack, StackResources};
+use embassy_stm32::eth::generic_smi::GenericSMI;
+use embassy_stm32::eth::{Ethernet, PacketQueue};
+use embassy_stm32::peripherals::ETH;
+use embassy_stm32::rng::Rng;
+use embassy_stm32::{bind_interrupts, eth, peripherals, rng, Config};
+use embassy_time::Timer;
+use embedded_io_async::Write;
+use embedded_nal_async::{Ipv4Addr, SocketAddr, SocketAddrV4, TcpConnect};
+use rand_core::RngCore;
+use static_cell::StaticCell;
+use {defmt_rtt as _, panic_probe as _};
+
+bind_interrupts!(struct Irqs {
+    ETH => eth::InterruptHandler;
+    RNG => rng::InterruptHandler<peripherals::RNG>;
+});
+
+type Device = Ethernet<'static, ETH, GenericSMI>;
+
+#[embassy_executor::task]
+async fn net_task(stack: &'static Stack<Device>) -> ! {
+    stack.run().await
+}
+
+#[embassy_executor::main]
+async fn main(spawner: Spawner) -> ! {
+    let mut config = Config::default();
+    {
+        use embassy_stm32::rcc::*;
+        config.rcc.hsi = Some(HSIPrescaler::DIV1);
+        config.rcc.csi = true;
+        config.rcc.hsi48 = Some(Default::default()); // needed for RNG
+        config.rcc.pll1 = Some(Pll {
+            source: PllSource::HSI,
+            prediv: PllPreDiv::DIV4,
+            mul: PllMul::MUL50,
+            divp: Some(PllDiv::DIV2),
+            divq: None,
+            divr: None,
+        });
+        config.rcc.sys = Sysclk::PLL1_P; // 400 Mhz
+        config.rcc.ahb_pre = AHBPrescaler::DIV2; // 200 Mhz
+        config.rcc.apb1_pre = APBPrescaler::DIV2; // 100 Mhz
+        config.rcc.apb2_pre = APBPrescaler::DIV2; // 100 Mhz
+        config.rcc.apb3_pre = APBPrescaler::DIV2; // 100 Mhz
+        config.rcc.apb4_pre = APBPrescaler::DIV2; // 100 Mhz
+        config.rcc.voltage_scale = VoltageScale::Scale1;
+    }
+    let p = embassy_stm32::init(config);
+    info!("Hello World!");
+
+    // Generate random seed.
+    let mut rng = Rng::new(p.RNG, Irqs);
+    let mut seed = [0; 8];
+    rng.fill_bytes(&mut seed);
+    let seed = u64::from_le_bytes(seed);
+
+    let mac_addr = [0x00, 0x00, 0xDE, 0xAD, 0xBE, 0xEF];
+
+    static PACKETS: StaticCell<PacketQueue<16, 16>> = StaticCell::new();
+
+    let device = Ethernet::new_mii(
+        PACKETS.init(PacketQueue::<16, 16>::new()),
+        p.ETH,
+        Irqs,
+        p.PA1,
+        p.PC3,
+        p.PA2,
+        p.PC1,
+        p.PA7,
+        p.PC4,
+        p.PC5,
+        p.PB0,
+        p.PB1,
+        p.PG13,
+        p.PG12,
+        p.PC2,
+        p.PE2,
+        p.PG11,
+        GenericSMI::new(1),
+        mac_addr,
+    );
+    info!("Device created");
+
+    let config = embassy_net::Config::dhcpv4(Default::default());
+    //let config = embassy_net::Config::ipv4_static(embassy_net::StaticConfigV4 {
+    //    address: Ipv4Cidr::new(Ipv4Address::new(10, 42, 0, 61), 24),
+    //    dns_servers: Vec::new(),
+    //    gateway: Some(Ipv4Address::new(10, 42, 0, 1)),
+    //});
+
+    // Init network stack
+    static STACK: StaticCell<Stack<Device>> = StaticCell::new();
+    static RESOURCES: StaticCell<StackResources<3>> = StaticCell::new();
+    let stack = &*STACK.init(Stack::new(
+        device,
+        config,
+        RESOURCES.init(StackResources::<3>::new()),
+        seed,
+    ));
+
+    // Launch network task
+    unwrap!(spawner.spawn(net_task(stack)));
+
+    // Ensure DHCP configuration is up before trying connect
+    stack.wait_config_up().await;
+
+    info!("Network task initialized");
+
+    let state: TcpClientState<1, 1024, 1024> = TcpClientState::new();
+    let client = TcpClient::new(&stack, &state);
+
+    loop {
+        // You need to start a server on the host machine, for example: `nc -l 8000`
+        let addr = SocketAddr::V4(SocketAddrV4::new(Ipv4Addr::new(192, 168, 100, 1), 8000));
+
+        info!("connecting...");
+        let r = client.connect(addr).await;
+        if let Err(e) = r {
+            info!("connect error: {:?}", e);
+            Timer::after_secs(1).await;
+            continue;
+        }
+        let mut connection = r.unwrap();
+        info!("connected!");
+        loop {
+            let r = connection.write_all(b"Hello\n").await;
+            if let Err(e) = r {
+                info!("write error: {:?}", e);
+                break;
+            }
+            Timer::after_secs(1).await;
+        }
+    }
+}
diff --git a/tests/nrf51422/.cargo/config.toml b/tests/nrf51422/.cargo/config.toml
new file mode 100644
index 000000000..634805633
--- /dev/null
+++ b/tests/nrf51422/.cargo/config.toml
@@ -0,0 +1,9 @@
+[target.'cfg(all(target_arch = "arm", target_os = "none"))']
+#runner = "teleprobe local run --chip nRF51422_xxAA --elf"
+runner = "teleprobe client run"
+
+[build]
+target = "thumbv6m-none-eabi"
+
+[env]
+DEFMT_LOG = "trace,embassy_hal_internal=debug"
diff --git a/tests/nrf51422/Cargo.toml b/tests/nrf51422/Cargo.toml
new file mode 100644
index 000000000..2cab20ac0
--- /dev/null
+++ b/tests/nrf51422/Cargo.toml
@@ -0,0 +1,22 @@
+[package]
+edition = "2021"
+name = "embassy-nrf51-tests"
+version = "0.1.0"
+license = "MIT OR Apache-2.0"
+
+[dependencies]
+teleprobe-meta = "1"
+
+embassy-sync = { version = "0.5.0", path = "../../embassy-sync", features = ["defmt", ] }
+embassy-executor = { version = "0.5.0", path = "../../embassy-executor", features = ["arch-cortex-m", "executor-thread", "defmt", "task-arena-size-128", "integrated-timers"] }
+embassy-time = { version = "0.3.0", path = "../../embassy-time", features = ["defmt",  "defmt-timestamp-uptime"] }
+embassy-nrf = { version = "0.1.0", path = "../../embassy-nrf", features = ["defmt",  "nrf51", "time-driver-rtc1", "unstable-pac", "time"] }
+embedded-io-async = { version = "0.6.1", features = ["defmt-03"] }
+embedded-hal-async = { version = "1.0" }
+
+defmt = "0.3"
+defmt-rtt = "0.4"
+
+cortex-m = { version = "0.7.6", features = ["critical-section-single-core"] }
+cortex-m-rt = "0.7.0"
+panic-probe = { version = "0.3", features = ["print-defmt"] }
diff --git a/tests/nrf51422/build.rs b/tests/nrf51422/build.rs
new file mode 100644
index 000000000..13ebbe4ee
--- /dev/null
+++ b/tests/nrf51422/build.rs
@@ -0,0 +1,17 @@
+use std::error::Error;
+use std::path::PathBuf;
+use std::{env, fs};
+
+fn main() -> Result<(), Box<dyn Error>> {
+    let out = PathBuf::from(env::var("OUT_DIR").unwrap());
+    fs::write(out.join("memory.x"), include_bytes!("memory.x")).unwrap();
+    println!("cargo:rustc-link-search={}", out.display());
+    println!("cargo:rerun-if-changed=memory.x");
+
+    println!("cargo:rustc-link-arg-bins=--nmagic");
+    println!("cargo:rustc-link-arg-bins=-Tlink.x");
+    println!("cargo:rustc-link-arg-bins=-Tdefmt.x");
+    println!("cargo:rustc-link-arg-bins=-Tteleprobe.x");
+
+    Ok(())
+}
diff --git a/tests/nrf51422/memory.x b/tests/nrf51422/memory.x
new file mode 100644
index 000000000..a5881e66f
--- /dev/null
+++ b/tests/nrf51422/memory.x
@@ -0,0 +1,5 @@
+MEMORY
+{
+  FLASH : ORIGIN = 0x00000000, LENGTH = 128K
+  RAM : ORIGIN = 0x20000000, LENGTH = 16K
+}
diff --git a/tests/nrf51422/src/bin/gpio.rs b/tests/nrf51422/src/bin/gpio.rs
new file mode 100644
index 000000000..6d5a87d0a
--- /dev/null
+++ b/tests/nrf51422/src/bin/gpio.rs
@@ -0,0 +1,28 @@
+#![no_std]
+#![no_main]
+teleprobe_meta::target!(b"nrf51-dk");
+
+use defmt::{assert, info};
+use embassy_executor::Spawner;
+use embassy_nrf::gpio::{Input, Level, Output, OutputDrive, Pull};
+use embassy_time::Timer;
+use {defmt_rtt as _, panic_probe as _};
+
+#[embassy_executor::main]
+async fn main(_spawner: Spawner) {
+    let p = embassy_nrf::init(Default::default());
+
+    let input = Input::new(p.P0_13, Pull::Up);
+    let mut output = Output::new(p.P0_14, Level::Low, OutputDrive::Standard);
+
+    output.set_low();
+    Timer::after_millis(10).await;
+    assert!(input.is_low());
+
+    output.set_high();
+    Timer::after_millis(10).await;
+    assert!(input.is_high());
+
+    info!("Test OK");
+    cortex_m::asm::bkpt();
+}
diff --git a/tests/nrf51422/src/bin/timer.rs b/tests/nrf51422/src/bin/timer.rs
new file mode 100644
index 000000000..cf9ea41a8
--- /dev/null
+++ b/tests/nrf51422/src/bin/timer.rs
@@ -0,0 +1,24 @@
+#![no_std]
+#![no_main]
+teleprobe_meta::target!(b"nrf51-dk");
+
+use defmt::{assert, info};
+use embassy_executor::Spawner;
+use embassy_time::{Instant, Timer};
+use {defmt_rtt as _, panic_probe as _};
+
+#[embassy_executor::main]
+async fn main(_spawner: Spawner) {
+    let _p = embassy_nrf::init(Default::default());
+    info!("Hello World!");
+
+    let start = Instant::now();
+    Timer::after_millis(100).await;
+    let end = Instant::now();
+    let ms = (end - start).as_millis();
+    info!("slept for {} ms", ms);
+    assert!(ms >= 99);
+
+    info!("Test OK");
+    cortex_m::asm::bkpt();
+}
diff --git a/tests/nrf/.cargo/config.toml b/tests/nrf52840/.cargo/config.toml
similarity index 100%
rename from tests/nrf/.cargo/config.toml
rename to tests/nrf52840/.cargo/config.toml
diff --git a/tests/nrf/Cargo.toml b/tests/nrf52840/Cargo.toml
similarity index 100%
rename from tests/nrf/Cargo.toml
rename to tests/nrf52840/Cargo.toml
diff --git a/tests/nrf/build.rs b/tests/nrf52840/build.rs
similarity index 100%
rename from tests/nrf/build.rs
rename to tests/nrf52840/build.rs
diff --git a/tests/nrf/memory.x b/tests/nrf52840/memory.x
similarity index 100%
rename from tests/nrf/memory.x
rename to tests/nrf52840/memory.x
diff --git a/tests/nrf/src/bin/buffered_uart.rs b/tests/nrf52840/src/bin/buffered_uart.rs
similarity index 100%
rename from tests/nrf/src/bin/buffered_uart.rs
rename to tests/nrf52840/src/bin/buffered_uart.rs
diff --git a/tests/nrf/src/bin/buffered_uart_full.rs b/tests/nrf52840/src/bin/buffered_uart_full.rs
similarity index 100%
rename from tests/nrf/src/bin/buffered_uart_full.rs
rename to tests/nrf52840/src/bin/buffered_uart_full.rs
diff --git a/tests/nrf/src/bin/buffered_uart_spam.rs b/tests/nrf52840/src/bin/buffered_uart_spam.rs
similarity index 100%
rename from tests/nrf/src/bin/buffered_uart_spam.rs
rename to tests/nrf52840/src/bin/buffered_uart_spam.rs
diff --git a/tests/nrf/src/bin/ethernet_enc28j60_perf.rs b/tests/nrf52840/src/bin/ethernet_enc28j60_perf.rs
similarity index 100%
rename from tests/nrf/src/bin/ethernet_enc28j60_perf.rs
rename to tests/nrf52840/src/bin/ethernet_enc28j60_perf.rs
diff --git a/tests/nrf/src/bin/timer.rs b/tests/nrf52840/src/bin/timer.rs
similarity index 96%
rename from tests/nrf/src/bin/timer.rs
rename to tests/nrf52840/src/bin/timer.rs
index 2a147e7ba..117947a94 100644
--- a/tests/nrf/src/bin/timer.rs
+++ b/tests/nrf52840/src/bin/timer.rs
@@ -18,7 +18,6 @@ async fn main(_spawner: Spawner) {
     let ms = (end - start).as_millis();
     info!("slept for {} ms", ms);
     assert!(ms >= 99);
-    assert!(ms < 110);
 
     info!("Test OK");
     cortex_m::asm::bkpt();
diff --git a/tests/nrf/src/bin/wifi_esp_hosted_perf.rs b/tests/nrf52840/src/bin/wifi_esp_hosted_perf.rs
similarity index 100%
rename from tests/nrf/src/bin/wifi_esp_hosted_perf.rs
rename to tests/nrf52840/src/bin/wifi_esp_hosted_perf.rs
diff --git a/tests/rp/src/bin/i2c.rs b/tests/rp/src/bin/i2c.rs
index 77d628cf6..a0aed1a42 100644
--- a/tests/rp/src/bin/i2c.rs
+++ b/tests/rp/src/bin/i2c.rs
@@ -80,7 +80,7 @@ async fn device_task(mut dev: i2c_slave::I2cSlave<'static, I2C1>) -> ! {
                 _ => panic!("Invalid write length {}", len),
             },
             Ok(i2c_slave::Command::WriteRead(len)) => {
-                info!("device recieved write read: {:x}", buf[..len]);
+                info!("device received write read: {:x}", buf[..len]);
                 match buf[0] {
                     0xC2 => {
                         let resp_buff = [0xD1, 0xD2, 0xD3, 0xD4];
diff --git a/tests/stm32/Cargo.toml b/tests/stm32/Cargo.toml
index bf85f05d2..cb1bd9a50 100644
--- a/tests/stm32/Cargo.toml
+++ b/tests/stm32/Cargo.toml
@@ -14,11 +14,11 @@ stm32f429zi = ["embassy-stm32/stm32f429zi", "chrono", "eth", "stop", "can", "not
 stm32f446re = ["embassy-stm32/stm32f446re", "chrono", "stop", "can", "not-gpdma", "dac", "sdmmc"]
 stm32f767zi = ["embassy-stm32/stm32f767zi", "chrono", "not-gpdma", "eth", "rng"]
 stm32g071rb = ["embassy-stm32/stm32g071rb", "cm0", "not-gpdma", "dac"]
-stm32g491re = ["embassy-stm32/stm32g491re", "chrono", "stop", "not-gpdma", "rng"]
+stm32g491re = ["embassy-stm32/stm32g491re", "chrono", "stop", "not-gpdma", "rng", "fdcan"]
 stm32h563zi = ["embassy-stm32/stm32h563zi", "chrono", "eth", "rng"]
-stm32h753zi = ["embassy-stm32/stm32h753zi", "chrono", "not-gpdma", "eth", "rng"]
-stm32h755zi = ["embassy-stm32/stm32h755zi-cm7", "chrono", "not-gpdma", "eth", "dac", "rng"]
-stm32h7a3zi = ["embassy-stm32/stm32h7a3zi", "not-gpdma", "rng"]
+stm32h753zi = ["embassy-stm32/stm32h753zi", "chrono", "not-gpdma", "eth", "rng", "fdcan"]
+stm32h755zi = ["embassy-stm32/stm32h755zi-cm7", "chrono", "not-gpdma", "eth", "dac", "rng", "fdcan"]
+stm32h7a3zi = ["embassy-stm32/stm32h7a3zi", "not-gpdma", "rng", "fdcan"]
 stm32l073rz = ["embassy-stm32/stm32l073rz", "cm0", "not-gpdma", "rng"]
 stm32l152re = ["embassy-stm32/stm32l152re", "chrono", "not-gpdma"]
 stm32l496zg = ["embassy-stm32/stm32l496zg", "not-gpdma", "rng"]
@@ -37,6 +37,7 @@ sdmmc = []
 stop = ["embassy-stm32/low-power", "embassy-stm32/low-power-debug-with-sleep"]
 chrono = ["embassy-stm32/chrono", "dep:chrono"]
 can = []
+fdcan = []
 ble = ["dep:embassy-stm32-wpan", "embassy-stm32-wpan/ble"]
 mac = ["dep:embassy-stm32-wpan", "embassy-stm32-wpan/mac"]
 embassy-stm32-wpan = []
@@ -96,6 +97,11 @@ name = "eth"
 path = "src/bin/eth.rs"
 required-features = [ "eth",]
 
+[[bin]]
+name = "fdcan"
+path = "src/bin/fdcan.rs"
+required-features = [ "fdcan",]
+
 [[bin]]
 name = "gpio"
 path = "src/bin/gpio.rs"
diff --git a/tests/stm32/src/bin/fdcan.rs b/tests/stm32/src/bin/fdcan.rs
new file mode 100644
index 000000000..7363eaa16
--- /dev/null
+++ b/tests/stm32/src/bin/fdcan.rs
@@ -0,0 +1,243 @@
+#![no_std]
+#![no_main]
+
+// required-features: fdcan
+
+#[path = "../common.rs"]
+mod common;
+use common::*;
+use defmt::assert;
+use embassy_executor::Spawner;
+use embassy_stm32::peripherals::*;
+use embassy_stm32::{bind_interrupts, can, Config};
+use embassy_time::{Duration, Instant};
+use {defmt_rtt as _, panic_probe as _};
+
+bind_interrupts!(struct Irqs {
+    FDCAN1_IT0 => can::IT0InterruptHandler<FDCAN1>;
+    FDCAN1_IT1 => can::IT1InterruptHandler<FDCAN1>;
+});
+
+struct TestOptions {
+    config: Config,
+    max_latency: Duration,
+    second_fifo_working: bool,
+}
+
+#[cfg(any(feature = "stm32h755zi", feature = "stm32h753zi", feature = "stm32h563zi"))]
+fn options() -> TestOptions {
+    use embassy_stm32::rcc;
+    info!("H75 config");
+    let mut c = config();
+    c.rcc.hse = Some(rcc::Hse {
+        freq: embassy_stm32::time::Hertz(25_000_000),
+        mode: rcc::HseMode::Oscillator,
+    });
+    c.rcc.fdcan_clock_source = rcc::FdCanClockSource::HSE;
+    TestOptions {
+        config: c,
+        max_latency: Duration::from_micros(3800),
+        second_fifo_working: false,
+    }
+}
+
+#[cfg(any(feature = "stm32h7a3zi"))]
+fn options() -> TestOptions {
+    use embassy_stm32::rcc;
+    info!("H7a config");
+    let mut c = config();
+    c.rcc.hse = Some(rcc::Hse {
+        freq: embassy_stm32::time::Hertz(25_000_000),
+        mode: rcc::HseMode::Oscillator,
+    });
+    c.rcc.fdcan_clock_source = rcc::FdCanClockSource::HSE;
+    TestOptions {
+        config: c,
+        max_latency: Duration::from_micros(5500),
+        second_fifo_working: false,
+    }
+}
+
+#[cfg(any(feature = "stm32g491re"))]
+fn options() -> TestOptions {
+    info!("G4 config");
+    TestOptions {
+        config: config(),
+        max_latency: Duration::from_micros(500),
+        second_fifo_working: true,
+    }
+}
+
+#[embassy_executor::main]
+async fn main(_spawner: Spawner) {
+    //let peripherals = embassy_stm32::init(config());
+
+    let options = options();
+    let peripherals = embassy_stm32::init(options.config);
+
+    let mut can = can::Fdcan::new(peripherals.FDCAN1, peripherals.PB8, peripherals.PB9, Irqs);
+
+    // 250k bps
+    can.set_bitrate(250_000);
+
+    can.can.set_extended_filter(
+        can::filter::ExtendedFilterSlot::_0,
+        can::filter::ExtendedFilter::accept_all_into_fifo1(),
+    );
+
+    let mut can = can.into_internal_loopback_mode();
+
+    info!("CAN Configured");
+
+    let mut i: u8 = 0;
+    loop {
+        let tx_frame = can::TxFrame::new(
+            can::TxFrameHeader {
+                len: 1,
+                frame_format: can::FrameFormat::Standard,
+                id: can::StandardId::new(0x123).unwrap().into(),
+                bit_rate_switching: false,
+                marker: None,
+            },
+            &[i],
+        )
+        .unwrap();
+
+        info!("Transmitting frame...");
+        let tx_ts = Instant::now();
+        can.write(&tx_frame).await;
+
+        let envelope = can.read().await.unwrap();
+        info!("Frame received!");
+
+        // Check data.
+        assert!(i == envelope.data()[0], "{} == {}", i, envelope.data()[0]);
+
+        info!("loopback time {}", envelope.header.time_stamp);
+        info!("loopback frame {=u8}", envelope.data()[0]);
+        let latency = envelope.timestamp.saturating_duration_since(tx_ts);
+        info!("loopback latency {} us", latency.as_micros());
+
+        // Theoretical minimum latency is 55us, actual is usually ~80us
+        const MIN_LATENCY: Duration = Duration::from_micros(50);
+        // Was failing at 150 but we are not getting a real time stamp. I'm not
+        // sure if there are other delays
+        assert!(
+            MIN_LATENCY <= latency && latency <= options.max_latency,
+            "{} <= {} <= {}",
+            MIN_LATENCY,
+            latency,
+            options.max_latency
+        );
+
+        i += 1;
+        if i > 10 {
+            break;
+        }
+    }
+
+    let max_buffered = if options.second_fifo_working { 6 } else { 3 };
+
+    // Below here, check that we can receive from both FIFO0 and FIFO0
+    // Above we configured FIFO1 for extended ID packets. There are only 3 slots
+    // in each FIFO so make sure we write enough to fill them both up before reading.
+    for i in 0..3 {
+        // Try filling up the RX FIFO0 buffers with standard packets
+        let tx_frame = can::TxFrame::new(
+            can::TxFrameHeader {
+                len: 1,
+                frame_format: can::FrameFormat::Standard,
+                id: can::StandardId::new(0x123).unwrap().into(),
+                bit_rate_switching: false,
+                marker: None,
+            },
+            &[i],
+        )
+        .unwrap();
+        info!("Transmitting frame {}", i);
+        can.write(&tx_frame).await;
+    }
+    for i in 3..max_buffered {
+        // Try filling up the RX FIFO0 buffers with extended packets
+        let tx_frame = can::TxFrame::new(
+            can::TxFrameHeader {
+                len: 1,
+                frame_format: can::FrameFormat::Standard,
+                id: can::ExtendedId::new(0x1232344).unwrap().into(),
+                bit_rate_switching: false,
+                marker: None,
+            },
+            &[i],
+        )
+        .unwrap();
+
+        info!("Transmitting frame {}", i);
+        can.write(&tx_frame).await;
+    }
+
+    // Try and receive all 6 packets
+    for i in 0..max_buffered {
+        let envelope = can.read().await.unwrap();
+        match envelope.header.id {
+            can::Id::Extended(id) => {
+                info!("Extended received! {:x} {} {}", id.as_raw(), envelope.data()[0], i);
+            }
+            can::Id::Standard(id) => {
+                info!("Standard received! {:x} {} {}", id.as_raw(), envelope.data()[0], i);
+            }
+        }
+    }
+
+    // Test again with a split
+    let (mut tx, mut rx) = can.split();
+    for i in 0..3 {
+        // Try filling up the RX FIFO0 buffers with standard packets
+        let tx_frame = can::TxFrame::new(
+            can::TxFrameHeader {
+                len: 1,
+                frame_format: can::FrameFormat::Standard,
+                id: can::StandardId::new(0x123).unwrap().into(),
+                bit_rate_switching: false,
+                marker: None,
+            },
+            &[i],
+        )
+        .unwrap();
+
+        info!("Transmitting frame {}", i);
+        tx.write(&tx_frame).await;
+    }
+    for i in 3..max_buffered {
+        // Try filling up the RX FIFO0 buffers with extended packets
+        let tx_frame = can::TxFrame::new(
+            can::TxFrameHeader {
+                len: 1,
+                frame_format: can::FrameFormat::Standard,
+                id: can::ExtendedId::new(0x1232344).unwrap().into(),
+                bit_rate_switching: false,
+                marker: None,
+            },
+            &[i],
+        )
+        .unwrap();
+
+        info!("Transmitting frame {}", i);
+        tx.write(&tx_frame).await;
+    }
+
+    // Try and receive all 6 packets
+    for i in 0..max_buffered {
+        let envelope = rx.read().await.unwrap();
+        match envelope.header.id {
+            can::Id::Extended(id) => {
+                info!("Extended received! {:x} {} {}", id.as_raw(), envelope.data()[0], i);
+            }
+            can::Id::Standard(id) => {
+                info!("Standard received! {:x} {} {}", id.as_raw(), envelope.data()[0], i);
+            }
+        }
+    }
+
+    info!("Test OK");
+    cortex_m::asm::bkpt();
+}