From 4167412fe8fae5720e6c6cc2450efb13bf891ab6 Mon Sep 17 00:00:00 2001 From: Justin Beaurivage Date: Sat, 22 Oct 2022 00:18:19 -0400 Subject: [PATCH] Try implementing async I2C (#6) --- boards/feather_m0/.cargo/config | 1 + boards/feather_m0/Cargo.toml | 8 + boards/feather_m0/examples/async_i2c.rs | 95 ++++++++++ boards/feather_m0/examples/async_timer.rs | 2 +- hal/Cargo.toml | 10 +- hal/src/async_hal/mod.rs | 32 ++-- hal/src/async_hal/timer.rs | 2 +- hal/src/sercom/i2c.rs | 6 + hal/src/sercom/i2c/async_api.rs | 202 ++++++++++++++++++++++ hal/src/sercom/i2c/flags.rs | 13 ++ hal/src/sercom/i2c/reg.rs | 49 ++++-- hal/src/sercom/mod.rs | 58 ++++++- 12 files changed, 437 insertions(+), 41 deletions(-) create mode 100644 boards/feather_m0/examples/async_i2c.rs create mode 100644 hal/src/sercom/i2c/async_api.rs diff --git a/boards/feather_m0/.cargo/config b/boards/feather_m0/.cargo/config index 01e807e22ffd..f3ee604d06ba 100644 --- a/boards/feather_m0/.cargo/config +++ b/boards/feather_m0/.cargo/config @@ -7,6 +7,7 @@ rustflags = [ # See https://github.com/rust-embedded/cortex-m-quickstart/pull/95 "-C", "link-arg=--nmagic", "-C", "link-arg=-Tlink.x", + "-C", "link-arg=-Tdefmt.x" ] [target.thumbv6m-none-eabi] diff --git a/boards/feather_m0/Cargo.toml b/boards/feather_m0/Cargo.toml index 813608f86838..417015320732 100644 --- a/boards/feather_m0/Cargo.toml +++ b/boards/feather_m0/Cargo.toml @@ -43,6 +43,7 @@ git = "https://github.com/datdenkikniet/cortex-m-interrupt.git" [dev-dependencies] cortex-m-rtic = "1.1.3" +fugit = "0.3.6" cortex-m = "0.7" usbd-serial = "0.1" cortex-m-semihosting = "0.3" @@ -53,6 +54,9 @@ nom = { version = "5", default-features = false } heapless = "0.7" panic-halt = "0.2" panic-semihosting = "0.5" +defmt = "0.3" +defmt-rtt = "0.3" +panic-probe = "0.3" [features] # ask the HAL to enable atsamd21g support @@ -154,5 +158,9 @@ required-features = ["dma"] name = "async_timer" required-features = ["atsamd-hal/async", "atsamd-hal/rtic", "cortex-m-interrupt"] +[[example]] +name = "async_i2c" +required-features = ["atsamd-hal/async", "atsamd-hal/rtic", "cortex-m-interrupt"] + [patch.crates-io] cortex-m-rtic = { git = "https://github.com/rtic-rs/cortex-m-rtic.git", branch = "async-2022" } diff --git a/boards/feather_m0/examples/async_i2c.rs b/boards/feather_m0/examples/async_i2c.rs new file mode 100644 index 000000000000..b8a8a68d562f --- /dev/null +++ b/boards/feather_m0/examples/async_i2c.rs @@ -0,0 +1,95 @@ +#![no_std] +#![no_main] +#![feature(type_alias_impl_trait)] + +use panic_probe as _; +use defmt_rtt as _; + +#[rtic::app(device = bsp::pac, dispatchers = [I2S])] +mod app { + use bsp::{hal, pac, pin_alias}; + use feather_m0 as bsp; + use hal::{ + prelude::*, + clock::{enable_internal_32kosc, ClockGenId, ClockSource, GenericClockController}, + ehal::digital::v2::ToggleableOutputPin, + rtc::{Count32Mode, Rtc}, + sercom::i2c::{self,Config, I2cFuture}, + }; + use fugit::MillisDuration; + + #[monotonic(binds = RTC, default = true)] + type Monotonic = Rtc; + + #[shared] + struct Shared {} + + #[local] + struct Local { + i2c: I2cFuture, bsp::pac::Interrupt>, + red_led: bsp::RedLed, + } + + #[init] + fn init(cx: init::Context) -> (Shared, Local, init::Monotonics) { + let mut peripherals = cx.device; + let _core = cx.core; + + let mut clocks = GenericClockController::with_external_32kosc( + peripherals.GCLK, + &mut peripherals.PM, + &mut peripherals.SYSCTRL, + &mut peripherals.NVMCTRL, + ); + let pins = bsp::Pins::new(peripherals.PORT); + let red_led: bsp::RedLed = pin_alias!(pins.red_led).into(); + + // Take SDA and SCL + let (sda, scl) = (pins.sda, pins.scl); + + let sercom3_irq = cortex_m_interrupt::take_nvic_interrupt!(pac::Interrupt::SERCOM3, 2); + // tc4_irq.set_priority(2); + + enable_internal_32kosc(&mut peripherals.SYSCTRL); + let timer_clock = clocks + .configure_gclk_divider_and_source(ClockGenId::GCLK2, 1, ClockSource::OSC32K, false) + .unwrap(); + clocks.configure_standby(ClockGenId::GCLK2, true); + + // Setup RTC monotonic + let rtc_clock = clocks.rtc(&timer_clock).unwrap(); + let rtc = Rtc::count32_mode(peripherals.RTC, rtc_clock.freq(), &mut peripherals.PM); + + let gclk0 = clocks.gclk0(); + let sercom3_clock = &clocks.sercom3_core(&gclk0).unwrap(); + let pads = i2c::Pads::new(sda, scl); + let i2c = i2c::Config::new(&peripherals.PM, peripherals.SERCOM3, pads, sercom3_clock.freq()) + .baud(100.khz()) + .enable().into_async(sercom3_irq); + + + async_task::spawn().ok(); + + (Shared {}, Local { i2c, red_led }, init::Monotonics(rtc)) + } + + #[task(local = [i2c, red_led])] + async fn async_task(cx: async_task::Context) { + let i2c = cx.local.i2c; + let red_led = cx.local.red_led; + + loop { + defmt::info!("Sending 1 byte to I2C..."); + // This test is based on the BMP388 barometer. Feel free to use any I2C peripheral + // you have on hand. + i2c.write(0x76, &[0x00]).await.unwrap(); + + let mut buffer = [0x00; 1]; + defmt::info!("Reading 1 byte from I2C..."); + i2c.read(0x76, &mut buffer).await.unwrap(); + defmt::info!("Chip ID is: {:#x}", buffer[0]); + red_led.toggle().unwrap(); + crate::app::monotonics::delay(MillisDuration::::from_ticks(500).convert()).await; + } + } +} diff --git a/boards/feather_m0/examples/async_timer.rs b/boards/feather_m0/examples/async_timer.rs index d42011a4d6fe..b37cd17ae593 100644 --- a/boards/feather_m0/examples/async_timer.rs +++ b/boards/feather_m0/examples/async_timer.rs @@ -63,7 +63,7 @@ mod app { // configure a clock for the TC4 and TC5 peripherals let tc45 = &clocks.tc4_tc5(&timer_clock).unwrap(); - // instantiate a timer objec for the TC3 peripheral + // instantiate a timer object for the TC4 peripheral let timer = TimerCounter::tc4_(tc45, peripherals.TC4, &mut peripherals.PM); let timer = timer.into_async(tc4_irq); async_task::spawn().ok(); diff --git a/hal/Cargo.toml b/hal/Cargo.toml index 4884604f5956..d1decb354ea3 100644 --- a/hal/Cargo.toml +++ b/hal/Cargo.toml @@ -93,8 +93,7 @@ atsame54n = {version = "0.13.0", path = "../pac/atsame54n", optional = true} atsame54p = {version = "0.13.0", path = "../pac/atsame54p", optional = true} [dependencies.embedded-hal-async] -version = "0.1.0-alph" -package = "embedded-hal" +version = "0.1.0-alpha.2" optional = true [dependencies.critical-section] @@ -105,12 +104,6 @@ optional = true version = "0.1" optional = true git = "https://github.com/embassy-rs/embassy.git" -# path = "../../../rust-projects/embassy/embassy-sync" - -[dependencies.futures] -version = "0.3.21" -optional = true -default-features = false [dependencies.cortex-m-interrupt] version = "0.1" @@ -214,7 +207,6 @@ usb = ["usb-device"] use_rtt = ["jlink_rtt"] async = [ "cortex-m-interrupt", - "futures", "critical-section", "unproven", "embassy-sync", diff --git a/hal/src/async_hal/mod.rs b/hal/src/async_hal/mod.rs index 0652f3f3242e..b0ea11052360 100644 --- a/hal/src/async_hal/mod.rs +++ b/hal/src/async_hal/mod.rs @@ -1,24 +1,24 @@ //! Async APIs -#[cfg(feature = "samd11")] -#[path = "irqs_samd11.rs"] -mod irqs; +// #[cfg(feature = "samd11")] +// #[path = "irqs_samd11.rs"] +// mod irqs; -#[cfg(feature = "samd21")] -#[path = "irqs_samd21.rs"] -mod irqs; +// #[cfg(feature = "samd21")] +// #[path = "irqs_samd21.rs"] +// mod irqs; -#[cfg(feature = "samd51")] -#[path = "irqs_thumbv7em.rs"] -mod irqs; +// #[cfg(feature = "samd51")] +// #[path = "irqs_thumbv7em.rs"] +// mod irqs; -pub mod interrupt { - pub use super::irqs::*; - pub use cortex_m::interrupt::{CriticalSection, Mutex}; - pub use embassy::interrupt::{declare, take, Interrupt}; +// pub mod interrupt { +// pub use super::irqs::*; +// pub use cortex_m::interrupt::{CriticalSection, Mutex}; +// pub use embassy::interrupt::{declare, take, Interrupt}; - // TODO Priority2 seems to only be true for thumbv6m chips - pub use embassy_hal_common::interrupt::Priority2 as Priority; -} +// // TODO Priority2 seems to only be true for thumbv6m chips +// pub use embassy_hal_common::interrupt::Priority2 as Priority; +// } pub mod timer; diff --git a/hal/src/async_hal/timer.rs b/hal/src/async_hal/timer.rs index 7918d58e6893..7398dea834b8 100644 --- a/hal/src/async_hal/timer.rs +++ b/hal/src/async_hal/timer.rs @@ -100,7 +100,7 @@ where #[inline] pub fn into_async(mut self, irq: I) -> AsyncTimer where - I: NvicInterruptHandle, + I: NvicInterruptHandle, N: InterruptNumber, { let irq_number = irq.number(); diff --git a/hal/src/sercom/i2c.rs b/hal/src/sercom/i2c.rs index 64e9225132a6..2958ddaeadfb 100644 --- a/hal/src/sercom/i2c.rs +++ b/hal/src/sercom/i2c.rs @@ -276,6 +276,12 @@ pub use config::*; mod impl_ehal; +#[cfg(feature = "async")] +mod async_api; + +#[cfg(feature = "async")] +pub use async_api::*; + /// Word size for an I2C message pub type Word = u8; diff --git a/hal/src/sercom/i2c/async_api.rs b/hal/src/sercom/i2c/async_api.rs new file mode 100644 index 000000000000..929e894bc43f --- /dev/null +++ b/hal/src/sercom/i2c/async_api.rs @@ -0,0 +1,202 @@ +use crate::sercom::{ + i2c::{self, AnyConfig, Flags, I2c}, + Sercom, +}; +use core::task::Poll; +use cortex_m::interrupt::InterruptNumber; +use cortex_m_interrupt::NvicInterruptHandle; + +impl I2c +where + C: AnyConfig, + S: Sercom, +{ + #[inline] + pub fn into_async(self, irq: I) -> I2cFuture + where + I: NvicInterruptHandle, + N: InterruptNumber, + { + let irq_number = irq.number(); + irq.register(S::on_interrupt_i2c); + unsafe { cortex_m::peripheral::NVIC::unmask(irq_number) }; + + I2cFuture { + i2c: self, + irq_number, + } + } +} + +pub struct I2cFuture +where + C: AnyConfig, + N: InterruptNumber, +{ + i2c: I2c, + irq_number: N, +} + +impl I2cFuture +where + C: AnyConfig, + S: Sercom, + N: InterruptNumber, +{ + /// Asynchronously write from a buffer. + #[inline] + pub async fn write(&mut self, addr: u8, bytes: &[u8]) -> Result<(), i2c::Error> { + self.i2c.config.as_mut().registers.start_write(addr)?; + + for b in bytes { + self.wait_flags(Flags::MB | Flags::ERROR).await; + self.i2c.read_status().check_bus_error()?; + + self.i2c.config.as_mut().registers.write_one(*b); + } + + self.i2c.cmd_stop(); + + Ok(()) + } + + /// Asynchronously read into a buffer. + #[inline] + pub async fn read(&mut self, addr: u8, buffer: &mut [u8]) -> Result<(), i2c::Error> { + self.i2c.config.as_mut().registers.start_read(addr)?; + + // Some manual iterator gumph because we need to ack bytes after the first. + let mut iter = buffer.iter_mut(); + *iter.next().expect("buffer len is at least 1") = self.read_one().await; + + loop { + match iter.next() { + None => break, + Some(dest) => { + // Ack the last byte so we can receive another one + self.i2c.config.as_mut().registers.cmd_read(); + *dest = self.read_one().await; + } + } + } + + // Arrange to send NACK on next command to + // stop slave from transmitting more data + self.i2c + .config + .as_mut() + .registers + .i2c_master() + .ctrlb + .modify(|_, w| w.ackact().set_bit()); + + Ok(()) + } + + /// Asynchronously write from a buffer, then read into a buffer. This is an extremely common pattern: writing a register address, then + /// read its value from the slave. + #[inline] + pub async fn write_read( + &mut self, + addr: u8, + write_buf: &[u8], + read_buf: &mut [u8], + ) -> Result<(), i2c::Error> { + self.write(addr, write_buf).await?; + self.read(addr, read_buf).await?; + Ok(()) + } + + async fn read_one(&mut self) -> u8 { + self.wait_flags(Flags::SB | Flags::ERROR).await; + self.i2c.config.as_mut().registers.read_one() + } + + async fn wait_flags(&mut self, flags_to_wait: Flags) { + core::future::poll_fn(|cx| { + S::waker().register(cx.waker()); + self.i2c.enable_interrupts(flags_to_wait); + let flags_to_check = self.i2c.config.as_ref().registers.read_flags(); + + if !flags_to_wait.intersects(flags_to_check) { + Poll::Pending + } else { + Poll::Ready(flags_to_check) + } + }) + .await; + } +} + +impl Drop for I2cFuture +where + C: AnyConfig, + N: InterruptNumber, +{ + fn drop(&mut self) { + cortex_m::peripheral::NVIC::mask(self.irq_number); + } +} + +#[cfg(feature = "nightly")] +mod impl_ehal { + use super::*; + use core::future::Future; + use embedded_hal_async::i2c::{ErrorType, I2c as I2cTrait, Operation}; + + impl ErrorType for I2cFuture + where + C: AnyConfig, + N: InterruptNumber, + { + type Error = i2c::Error; + } + + impl I2cTrait for I2cFuture + where + C: AnyConfig, + N: InterruptNumber, + { + type ReadFuture<'a> = impl Future> + 'a where Self: 'a; + + fn read<'a>(&'a mut self, address: u8, buffer: &'a mut [u8]) -> Self::ReadFuture<'a> { + self.read(address, buffer) + } + + type WriteFuture<'a> = impl Future> + 'a where Self: 'a; + + fn write<'a>(&'a mut self, address: u8, bytes: &'a [u8]) -> Self::WriteFuture<'a> { + self.write(address, bytes) + } + + type WriteReadFuture<'a> = impl Future> + 'a where Self: 'a; + + fn write_read<'a>( + &'a mut self, + address: u8, + wr_buffer: &'a [u8], + rd_buffer: &'a mut [u8], + ) -> Self::WriteReadFuture<'a> { + self.write_read(address, wr_buffer, rd_buffer) + } + + type TransactionFuture<'a, 'b> = impl Future> + 'a where Self: 'a, 'b: 'a; + + fn transaction<'a, 'b>( + &'a mut self, + address: u8, + operations: &'a mut [embedded_hal_async::i2c::Operation<'b>], + ) -> Self::TransactionFuture<'a, 'b> { + async move { + for op in operations { + match op { + Operation::Read(buf) => self.read(address, buf).await?, + Operation::Write(buf) => self.write(address, buf).await?, + } + } + + Ok(()) + } + } + } +} diff --git a/hal/src/sercom/i2c/flags.rs b/hal/src/sercom/i2c/flags.rs index 4ee40561afbf..065a377099cf 100644 --- a/hal/src/sercom/i2c/flags.rs +++ b/hal/src/sercom/i2c/flags.rs @@ -82,3 +82,16 @@ pub enum Error { Nack, Timeout, } + +#[cfg(feature = "nightly")] +impl embedded_hal_async::i2c::Error for Error { + fn kind(&self) -> embedded_hal_async::i2c::ErrorKind { + use embedded_hal_async::i2c::{ErrorKind, NoAcknowledgeSource}; + match self { + Error::ArbitrationLost => ErrorKind::ArbitrationLoss, + Error::BusError => ErrorKind::Bus, + Error::LengthError | Error::Timeout => ErrorKind::Overrun, + Error::Nack => ErrorKind::NoAcknowledge(NoAcknowledgeSource::Unknown), + } + } +} diff --git a/hal/src/sercom/i2c/reg.rs b/hal/src/sercom/i2c/reg.rs index d8f59cc64b1d..f2ee64a0554e 100644 --- a/hal/src/sercom/i2c/reg.rs +++ b/hal/src/sercom/i2c/reg.rs @@ -27,7 +27,7 @@ impl Registers { /// Helper function to access the underlying `I2CM` from the given `SERCOM` #[inline] - fn i2c_master(&self) -> &pac::sercom0::I2CM { + pub(crate) fn i2c_master(&self) -> &pac::sercom0::I2CM { self.sercom.i2cm() } @@ -209,9 +209,9 @@ impl Registers { } } - /// Start a blocking write transaction + /// Start a write transaction. May be used by [`start_write_blocking`], or an async method. #[inline] - pub(super) fn start_write_blocking(&mut self, addr: u8) -> Result<(), Error> { + pub(super) fn start_write(&mut self, addr: u8) -> Result<(), Error> { if self.get_smart_mode() { self.disable(); self.set_smart_mode(false); @@ -228,14 +228,21 @@ impl Registers { .write(|w| w.addr().bits(encode_write_address(addr))); } + Ok(()) + } + + /// Start a blocking write transaction + #[inline] + pub(super) fn start_write_blocking(&mut self, addr: u8) -> Result<(), Error> { + self.start_write(addr)?; + // wait for transmission to complete while !self.i2c_master().intflag.read().mb().bit_is_set() {} self.read_status().check_bus_error() } - /// Start a blocking read transaction - #[inline] - pub(super) fn start_read_blocking(&mut self, addr: u8) -> Result<(), Error> { + /// Start a write transaction. May be used by [`start_write_blocking`], or an async method. + pub(super) fn start_read(&mut self, addr: u8) -> Result<(), Error> { if self.get_smart_mode() { self.disable(); self.set_smart_mode(false); @@ -256,6 +263,14 @@ impl Registers { .write(|w| w.addr().bits(encode_read_address(addr))); } + Ok(()) + } + + /// Start a blocking read transaction + #[inline] + pub(super) fn start_read_blocking(&mut self, addr: u8) -> Result<(), Error> { + self.start_read(addr)?; + // wait for transmission to complete loop { let intflag = self.i2c_master().intflag.read(); @@ -347,12 +362,17 @@ impl Registers { self.sync_sysop(); } + #[inline] + pub(super) fn write_one(&mut self, byte: u8) { + unsafe { + self.i2c_master().data.write(|w| w.bits(byte)); + } + } + #[inline] pub(super) fn send_bytes(&mut self, bytes: &[u8]) -> Result<(), Error> { for b in bytes { - unsafe { - self.i2c_master().data.write(|w| w.bits(*b)); - } + self.write_one(*b); loop { let intflag = self.i2c_master().intflag.read(); @@ -367,15 +387,20 @@ impl Registers { #[inline] pub(super) fn read_one(&mut self) -> u8 { - while !self.i2c_master().intflag.read().sb().bit_is_set() {} self.i2c_master().data.read().bits() } + #[inline] + pub(super) fn read_one_blocking(&mut self) -> u8 { + while !self.i2c_master().intflag.read().sb().bit_is_set() {} + self.read_one() + } + #[inline] pub(super) fn fill_buffer(&mut self, buffer: &mut [u8]) -> Result<(), Error> { // Some manual iterator gumph because we need to ack bytes after the first. let mut iter = buffer.iter_mut(); - *iter.next().expect("buffer len is at least 1") = self.read_one(); + *iter.next().expect("buffer len is at least 1") = self.read_one_blocking(); loop { match iter.next() { @@ -383,7 +408,7 @@ impl Registers { Some(dest) => { // Ack the last byte so that we can receive another one self.cmd_read(); - *dest = self.read_one(); + *dest = self.read_one_blocking(); } } } diff --git a/hal/src/sercom/mod.rs b/hal/src/sercom/mod.rs index a1d2d0a04ae9..110962bd8ead 100644 --- a/hal/src/sercom/mod.rs +++ b/hal/src/sercom/mod.rs @@ -36,8 +36,7 @@ use core::ops::Deref; use paste::paste; use seq_macro::seq; -use crate::pac; -use pac::sercom0; +use crate::pac::{self, Peripherals}; #[cfg(feature = "thumbv7")] use pac::MCLK as APB_CLK_CTRL; @@ -76,6 +75,17 @@ pub trait Sercom: Sealed + Deref { const DMA_TX_TRIGGER: TriggerSource; /// Enable the corresponding APB clock fn enable_apb_clock(&mut self, ctrl: &APB_CLK_CTRL); + /// Get a reference to the sercom from a + /// [`Peripherals`](crate::pac::Peripherals) block + fn reg_block(peripherals: &mut Peripherals) -> &crate::pac::sercom0::RegisterBlock; + /// Interrupt handler for async I2C operarions + #[cfg(feature = "async")] + fn on_interrupt_i2c(); + /// Get a reference to this [`Sercom`]'s associated Waker + #[cfg(feature = "async")] + fn waker() -> &'static embassy_sync::waitqueue::AtomicWaker { + &waker::WAKERS[Self::NUM] + } } macro_rules! sercom { @@ -92,14 +102,41 @@ macro_rules! sercom { #[cfg(feature = "has-" sercom~N)] impl Sercom for Sercom~N { const NUM: usize = N; + #[cfg(feature = "dma")] const DMA_RX_TRIGGER: TriggerSource = TriggerSource::[]; + #[cfg(feature = "dma")] const DMA_TX_TRIGGER: TriggerSource = TriggerSource::[]; + #[inline] fn enable_apb_clock(&mut self, ctrl: &APB_CLK_CTRL) { ctrl.$apbmask.modify(|_, w| w.[]().set_bit()); } + + #[inline] + fn reg_block(peripherals: &mut Peripherals) -> &crate::pac::sercom0::RegisterBlock { + &*peripherals.SERCOM~N + } + + /// Interrupt handler for async I2C operarions + /// TODO the ISR gets called twice on every MB request??? + #[cfg(feature = "async")] + #[inline] + fn on_interrupt_i2c(){ + use self::i2c::Flags; + let mut peripherals = unsafe { crate::pac::Peripherals::steal() }; + let i2cm = Self::reg_block(&mut peripherals).i2cm(); + let flags_to_check = Flags::MB | Flags::SB | Flags::ERROR; + let flags_pending = Flags::from_bits_truncate(i2cm.intflag.read().bits()); + + // Disable interrupts, but don't clear the flags. The future will take care of + // clearing flags and re-enabling interrupts when woken. + if flags_to_check.contains(flags_pending) { + i2cm.intenclr.write(|w| unsafe { w.bits(flags_pending.bits()) } ); + waker::WAKERS[Self::NUM].wake(); + } + } } } }); @@ -115,3 +152,20 @@ sercom!(apbamask: (0, 1)); sercom!(apbbmask: (2, 3)); #[cfg(feature = "thumbv7")] sercom!(apbdmask: (4, 7)); + +#[cfg(feature = "samd11")] +const NUM_SERCOM: usize = 2; +#[cfg(feature = "samd21e")] +const NUM_SERCOM: usize = 4; +#[cfg(any(feature = "min-samd21g", feature = "samd51g", feature = "samd51j"))] +const NUM_SERCOM: usize = 6; +#[cfg(feature = "min-samd51n")] +const NUM_SERCOM: usize = 8; + +#[cfg(feature = "async")] +pub(super) mod waker { + use embassy_sync::waitqueue::AtomicWaker; + #[allow(clippy::declare_interior_mutable_const)] + const NEW_WAKER: AtomicWaker = AtomicWaker::new(); + pub(super) static WAKERS: [AtomicWaker; super::NUM_SERCOM] = [NEW_WAKER; super::NUM_SERCOM]; +}