From a84b33995eacc32e0e13d70293fa9bd7b2bd75f8 Mon Sep 17 00:00:00 2001 From: Dario Nieuwenhuis Date: Fri, 5 Apr 2024 00:35:25 +0200 Subject: [PATCH] rp: remove mod sealed. --- embassy-rp/src/adc.rs | 24 ++++---- embassy-rp/src/clocks.rs | 11 ++-- embassy-rp/src/dma.rs | 23 ++++--- embassy-rp/src/flash.rs | 16 ++--- embassy-rp/src/gpio.rs | 96 ++++++++++++++---------------- embassy-rp/src/i2c.rs | 51 +++++++--------- embassy-rp/src/pio/mod.rs | 64 ++++++++++---------- embassy-rp/src/pwm.rs | 12 ++-- embassy-rp/src/rtc/mod.rs | 11 ++-- embassy-rp/src/spi.rs | 27 ++++----- embassy-rp/src/uart/mod.rs | 55 ++++++++--------- embassy-rp/src/usb.rs | 13 ++-- examples/rp/src/bin/pio_stepper.rs | 2 +- 13 files changed, 189 insertions(+), 216 deletions(-) diff --git a/embassy-rp/src/adc.rs b/embassy-rp/src/adc.rs index 4c01fe195..101c5b71f 100644 --- a/embassy-rp/src/adc.rs +++ b/embassy-rp/src/adc.rs @@ -8,8 +8,7 @@ use core::task::Poll; use embassy_hal_internal::{into_ref, PeripheralRef}; use embassy_sync::waitqueue::AtomicWaker; -use crate::gpio::sealed::Pin as GpioPin; -use crate::gpio::{self, AnyPin, Pull}; +use crate::gpio::{self, AnyPin, Pull, SealedPin as GpioPin}; use crate::interrupt::typelevel::Binding; use crate::interrupt::InterruptExt; use crate::peripherals::{ADC, ADC_TEMP_SENSOR}; @@ -334,29 +333,28 @@ impl interrupt::typelevel::Handler for Inter } } -mod sealed { - pub trait AdcSample: crate::dma::Word {} - - pub trait AdcChannel {} -} +trait SealedAdcSample: crate::dma::Word {} +trait SealedAdcChannel {} /// ADC sample. -pub trait AdcSample: sealed::AdcSample {} +#[allow(private_bounds)] +pub trait AdcSample: SealedAdcSample {} -impl sealed::AdcSample for u16 {} +impl SealedAdcSample for u16 {} impl AdcSample for u16 {} -impl sealed::AdcSample for u8 {} +impl SealedAdcSample for u8 {} impl AdcSample for u8 {} /// ADC channel. -pub trait AdcChannel: sealed::AdcChannel {} +#[allow(private_bounds)] +pub trait AdcChannel: SealedAdcChannel {} /// ADC pin. pub trait AdcPin: AdcChannel + gpio::Pin {} macro_rules! impl_pin { ($pin:ident, $channel:expr) => { - impl sealed::AdcChannel for peripherals::$pin {} + impl SealedAdcChannel for peripherals::$pin {} impl AdcChannel for peripherals::$pin {} impl AdcPin for peripherals::$pin {} }; @@ -367,5 +365,5 @@ impl_pin!(PIN_27, 1); impl_pin!(PIN_28, 2); impl_pin!(PIN_29, 3); -impl sealed::AdcChannel for peripherals::ADC_TEMP_SENSOR {} +impl SealedAdcChannel for peripherals::ADC_TEMP_SENSOR {} impl AdcChannel for peripherals::ADC_TEMP_SENSOR {} diff --git a/embassy-rp/src/clocks.rs b/embassy-rp/src/clocks.rs index b7f6aeac9..bedb79464 100644 --- a/embassy-rp/src/clocks.rs +++ b/embassy-rp/src/clocks.rs @@ -6,8 +6,7 @@ use core::sync::atomic::{AtomicU16, AtomicU32, Ordering}; use embassy_hal_internal::{into_ref, PeripheralRef}; use pac::clocks::vals::*; -use crate::gpio::sealed::Pin; -use crate::gpio::AnyPin; +use crate::gpio::{AnyPin, SealedPin}; use crate::pac::common::{Reg, RW}; use crate::{pac, reset, Peripheral}; @@ -788,14 +787,14 @@ impl_gpinpin!(PIN_20, 20, 0); impl_gpinpin!(PIN_22, 22, 1); /// General purpose clock input driver. -pub struct Gpin<'d, T: Pin> { +pub struct Gpin<'d, T: GpinPin> { gpin: PeripheralRef<'d, AnyPin>, _phantom: PhantomData, } -impl<'d, T: Pin> Gpin<'d, T> { +impl<'d, T: GpinPin> Gpin<'d, T> { /// Create new gpin driver. - pub fn new(gpin: impl Peripheral

+ 'd) -> Gpin<'d, P> { + pub fn new(gpin: impl Peripheral

+ 'd) -> Self { into_ref!(gpin); gpin.gpio().ctrl().write(|w| w.set_funcsel(0x08)); @@ -811,7 +810,7 @@ impl<'d, T: Pin> Gpin<'d, T> { // } } -impl<'d, T: Pin> Drop for Gpin<'d, T> { +impl<'d, T: GpinPin> Drop for Gpin<'d, T> { fn drop(&mut self) { self.gpin .gpio() diff --git a/embassy-rp/src/dma.rs b/embassy-rp/src/dma.rs index 44aabce6b..e6374a86c 100644 --- a/embassy-rp/src/dma.rs +++ b/embassy-rp/src/dma.rs @@ -208,14 +208,12 @@ pub(crate) const CHANNEL_COUNT: usize = 12; const NEW_AW: AtomicWaker = AtomicWaker::new(); static CHANNEL_WAKERS: [AtomicWaker; CHANNEL_COUNT] = [NEW_AW; CHANNEL_COUNT]; -mod sealed { - pub trait Channel {} - - pub trait Word {} -} +trait SealedChannel {} +trait SealedWord {} /// DMA channel interface. -pub trait Channel: Peripheral

+ sealed::Channel + Into + Sized + 'static { +#[allow(private_bounds)] +pub trait Channel: Peripheral

+ SealedChannel + Into + Sized + 'static { /// Channel number. fn number(&self) -> u8; @@ -231,26 +229,27 @@ pub trait Channel: Peripheral

+ sealed::Channel + Into + S } /// DMA word. -pub trait Word: sealed::Word { +#[allow(private_bounds)] +pub trait Word: SealedWord { /// Word size. fn size() -> vals::DataSize; } -impl sealed::Word for u8 {} +impl SealedWord for u8 {} impl Word for u8 { fn size() -> vals::DataSize { vals::DataSize::SIZE_BYTE } } -impl sealed::Word for u16 {} +impl SealedWord for u16 {} impl Word for u16 { fn size() -> vals::DataSize { vals::DataSize::SIZE_HALFWORD } } -impl sealed::Word for u32 {} +impl SealedWord for u32 {} impl Word for u32 { fn size() -> vals::DataSize { vals::DataSize::SIZE_WORD @@ -264,7 +263,7 @@ pub struct AnyChannel { impl_peripheral!(AnyChannel); -impl sealed::Channel for AnyChannel {} +impl SealedChannel for AnyChannel {} impl Channel for AnyChannel { fn number(&self) -> u8 { self.number @@ -273,7 +272,7 @@ impl Channel for AnyChannel { macro_rules! channel { ($name:ident, $num:expr) => { - impl sealed::Channel for peripherals::$name {} + impl SealedChannel for peripherals::$name {} impl Channel for peripherals::$name { fn number(&self) -> u8 { $num diff --git a/embassy-rp/src/flash.rs b/embassy-rp/src/flash.rs index 422b77400..45b385cb4 100644 --- a/embassy-rp/src/flash.rs +++ b/embassy-rp/src/flash.rs @@ -903,22 +903,22 @@ pub(crate) unsafe fn in_ram(operation: impl FnOnce()) -> Result<(), Error> { Ok(()) } -mod sealed { - pub trait Instance {} - pub trait Mode {} -} +trait SealedInstance {} +trait SealedMode {} /// Flash instance. -pub trait Instance: sealed::Instance {} +#[allow(private_bounds)] +pub trait Instance: SealedInstance {} /// Flash mode. -pub trait Mode: sealed::Mode {} +#[allow(private_bounds)] +pub trait Mode: SealedMode {} -impl sealed::Instance for FLASH {} +impl SealedInstance for FLASH {} impl Instance for FLASH {} macro_rules! impl_mode { ($name:ident) => { - impl sealed::Mode for $name {} + impl SealedMode for $name {} impl Mode for $name {} }; } diff --git a/embassy-rp/src/gpio.rs b/embassy-rp/src/gpio.rs index a84c00a2c..ea87fd9da 100644 --- a/embassy-rp/src/gpio.rs +++ b/embassy-rp/src/gpio.rs @@ -8,7 +8,6 @@ use core::task::{Context, Poll}; use embassy_hal_internal::{impl_peripheral, into_ref, PeripheralRef}; use embassy_sync::waitqueue::AtomicWaker; -use self::sealed::Pin as _; use crate::interrupt::InterruptExt; use crate::pac::common::{Reg, RW}; use crate::pac::SIO; @@ -802,68 +801,65 @@ impl<'w> Drop for DormantWake<'w> { } } -pub(crate) mod sealed { - use super::*; +pub(crate) trait SealedPin: Sized { + fn pin_bank(&self) -> u8; - pub trait Pin: Sized { - fn pin_bank(&self) -> u8; + #[inline] + fn _pin(&self) -> u8 { + self.pin_bank() & 0x1f + } - #[inline] - fn _pin(&self) -> u8 { - self.pin_bank() & 0x1f + #[inline] + fn _bank(&self) -> Bank { + match self.pin_bank() >> 5 { + #[cfg(feature = "qspi-as-gpio")] + 1 => Bank::Qspi, + _ => Bank::Bank0, } + } - #[inline] - fn _bank(&self) -> Bank { - match self.pin_bank() >> 5 { - #[cfg(feature = "qspi-as-gpio")] - 1 => Bank::Qspi, - _ => Bank::Bank0, - } + fn io(&self) -> pac::io::Io { + match self._bank() { + Bank::Bank0 => crate::pac::IO_BANK0, + #[cfg(feature = "qspi-as-gpio")] + Bank::Qspi => crate::pac::IO_QSPI, } + } - fn io(&self) -> pac::io::Io { - match self._bank() { - Bank::Bank0 => crate::pac::IO_BANK0, - #[cfg(feature = "qspi-as-gpio")] - Bank::Qspi => crate::pac::IO_QSPI, - } - } + fn gpio(&self) -> pac::io::Gpio { + self.io().gpio(self._pin() as _) + } - fn gpio(&self) -> pac::io::Gpio { - self.io().gpio(self._pin() as _) - } + fn pad_ctrl(&self) -> Reg { + let block = match self._bank() { + Bank::Bank0 => crate::pac::PADS_BANK0, + #[cfg(feature = "qspi-as-gpio")] + Bank::Qspi => crate::pac::PADS_QSPI, + }; + block.gpio(self._pin() as _) + } - fn pad_ctrl(&self) -> Reg { - let block = match self._bank() { - Bank::Bank0 => crate::pac::PADS_BANK0, - #[cfg(feature = "qspi-as-gpio")] - Bank::Qspi => crate::pac::PADS_QSPI, - }; - block.gpio(self._pin() as _) - } + fn sio_out(&self) -> pac::sio::Gpio { + SIO.gpio_out(self._bank() as _) + } - fn sio_out(&self) -> pac::sio::Gpio { - SIO.gpio_out(self._bank() as _) - } + fn sio_oe(&self) -> pac::sio::Gpio { + SIO.gpio_oe(self._bank() as _) + } - fn sio_oe(&self) -> pac::sio::Gpio { - SIO.gpio_oe(self._bank() as _) - } + fn sio_in(&self) -> Reg { + SIO.gpio_in(self._bank() as _) + } - fn sio_in(&self) -> Reg { - SIO.gpio_in(self._bank() as _) - } - - fn int_proc(&self) -> pac::io::Int { - let proc = SIO.cpuid().read(); - self.io().int_proc(proc as _) - } + fn int_proc(&self) -> pac::io::Int { + let proc = SIO.cpuid().read(); + self.io().int_proc(proc as _) } } /// Interface for a Pin that can be configured by an [Input] or [Output] driver, or converted to an [AnyPin]. -pub trait Pin: Peripheral

+ Into + sealed::Pin + Sized + 'static { +#[allow(private_bounds)] +pub trait Pin: Peripheral

+ Into + SealedPin + Sized + 'static { /// Degrade to a generic pin struct fn degrade(self) -> AnyPin { AnyPin { @@ -903,7 +899,7 @@ impl AnyPin { impl_peripheral!(AnyPin); impl Pin for AnyPin {} -impl sealed::Pin for AnyPin { +impl SealedPin for AnyPin { fn pin_bank(&self) -> u8 { self.pin_bank } @@ -914,7 +910,7 @@ impl sealed::Pin for AnyPin { macro_rules! impl_pin { ($name:ident, $bank:expr, $pin_num:expr) => { impl Pin for peripherals::$name {} - impl sealed::Pin for peripherals::$name { + impl SealedPin for peripherals::$name { #[inline] fn pin_bank(&self) -> u8 { ($bank as u8) * 32 + $pin_num diff --git a/embassy-rp/src/i2c.rs b/embassy-rp/src/i2c.rs index 26a819b25..256875b4a 100644 --- a/embassy-rp/src/i2c.rs +++ b/embassy-rp/src/i2c.rs @@ -784,34 +784,24 @@ pub fn i2c_reserved_addr(addr: u16) -> bool { ((addr & 0x78) == 0 || (addr & 0x78) == 0x78) && addr != 0 } -mod sealed { - use embassy_sync::waitqueue::AtomicWaker; +pub(crate) trait SealedInstance { + const TX_DREQ: u8; + const RX_DREQ: u8; - use crate::interrupt; - - pub trait Instance { - const TX_DREQ: u8; - const RX_DREQ: u8; - - type Interrupt: interrupt::typelevel::Interrupt; - - fn regs() -> crate::pac::i2c::I2c; - fn reset() -> crate::pac::resets::regs::Peripherals; - fn waker() -> &'static AtomicWaker; - } - - pub trait Mode {} - - pub trait SdaPin {} - pub trait SclPin {} + fn regs() -> crate::pac::i2c::I2c; + fn reset() -> crate::pac::resets::regs::Peripherals; + fn waker() -> &'static AtomicWaker; } +trait SealedMode {} + /// Driver mode. -pub trait Mode: sealed::Mode {} +#[allow(private_bounds)] +pub trait Mode: SealedMode {} macro_rules! impl_mode { ($name:ident) => { - impl sealed::Mode for $name {} + impl SealedMode for $name {} impl Mode for $name {} }; } @@ -825,16 +815,18 @@ impl_mode!(Blocking); impl_mode!(Async); /// I2C instance. -pub trait Instance: sealed::Instance {} +#[allow(private_bounds)] +pub trait Instance: SealedInstance { + /// Interrupt for this peripheral. + type Interrupt: interrupt::typelevel::Interrupt; +} macro_rules! impl_instance { ($type:ident, $irq:ident, $reset:ident, $tx_dreq:expr, $rx_dreq:expr) => { - impl sealed::Instance for peripherals::$type { + impl SealedInstance for peripherals::$type { const TX_DREQ: u8 = $tx_dreq; const RX_DREQ: u8 = $rx_dreq; - type Interrupt = crate::interrupt::typelevel::$irq; - #[inline] fn regs() -> pac::i2c::I2c { pac::$type @@ -854,7 +846,9 @@ macro_rules! impl_instance { &WAKER } } - impl Instance for peripherals::$type {} + impl Instance for peripherals::$type { + type Interrupt = crate::interrupt::typelevel::$irq; + } }; } @@ -862,13 +856,12 @@ impl_instance!(I2C0, I2C0_IRQ, set_i2c0, 32, 33); impl_instance!(I2C1, I2C1_IRQ, set_i2c1, 34, 35); /// SDA pin. -pub trait SdaPin: sealed::SdaPin + crate::gpio::Pin {} +pub trait SdaPin: crate::gpio::Pin {} /// SCL pin. -pub trait SclPin: sealed::SclPin + crate::gpio::Pin {} +pub trait SclPin: crate::gpio::Pin {} macro_rules! impl_pin { ($pin:ident, $instance:ident, $function:ident) => { - impl sealed::$function for peripherals::$pin {} impl $function for peripherals::$pin {} }; } diff --git a/embassy-rp/src/pio/mod.rs b/embassy-rp/src/pio/mod.rs index 7eca700ba..2e5c57a26 100644 --- a/embassy-rp/src/pio/mod.rs +++ b/embassy-rp/src/pio/mod.rs @@ -15,8 +15,7 @@ use pac::pio::vals::SmExecctrlStatusSel; use pio::{Program, SideSet, Wrap}; use crate::dma::{Channel, Transfer, Word}; -use crate::gpio::sealed::Pin as SealedPin; -use crate::gpio::{self, AnyPin, Drive, Level, Pull, SlewRate}; +use crate::gpio::{self, AnyPin, Drive, Level, Pull, SealedPin, SlewRate}; use crate::interrupt::typelevel::{Binding, Handler, Interrupt}; use crate::pac::dma::vals::TreqSel; use crate::relocate::RelocatedProgram; @@ -695,6 +694,12 @@ impl<'d, PIO: Instance + 'd, const SM: usize> StateMachine<'d, PIO, SM> { } } + /// Set the clock divider for this state machine. + pub fn set_clock_divider(&mut self, clock_divider: FixedU32) { + let sm = Self::this_sm(); + sm.clkdiv().write(|w| w.0 = clock_divider.to_bits() << 8); + } + #[inline(always)] fn this_sm() -> crate::pac::pio::StateMachine { PIO::PIO.sm(SM) @@ -1148,49 +1153,47 @@ fn on_pio_drop() { } } -mod sealed { - use super::*; +trait SealedInstance { + const PIO_NO: u8; + const PIO: &'static crate::pac::pio::Pio; + const FUNCSEL: crate::pac::io::vals::Gpio0ctrlFuncsel; - pub trait PioPin {} + #[inline] + fn wakers() -> &'static Wakers { + const NEW_AW: AtomicWaker = AtomicWaker::new(); + static WAKERS: Wakers = Wakers([NEW_AW; 12]); - pub trait Instance { - const PIO_NO: u8; - const PIO: &'static crate::pac::pio::Pio; - const FUNCSEL: crate::pac::io::vals::Gpio0ctrlFuncsel; - type Interrupt: crate::interrupt::typelevel::Interrupt; + &WAKERS + } - #[inline] - fn wakers() -> &'static Wakers { - const NEW_AW: AtomicWaker = AtomicWaker::new(); - static WAKERS: Wakers = Wakers([NEW_AW; 12]); + #[inline] + fn state() -> &'static State { + static STATE: State = State { + users: AtomicU8::new(0), + used_pins: AtomicU32::new(0), + }; - &WAKERS - } - - #[inline] - fn state() -> &'static State { - static STATE: State = State { - users: AtomicU8::new(0), - used_pins: AtomicU32::new(0), - }; - - &STATE - } + &STATE } } /// PIO instance. -pub trait Instance: sealed::Instance + Sized + Unpin {} +#[allow(private_bounds)] +pub trait Instance: SealedInstance + Sized + Unpin { + /// Interrupt for this peripheral. + type Interrupt: crate::interrupt::typelevel::Interrupt; +} macro_rules! impl_pio { ($name:ident, $pio:expr, $pac:ident, $funcsel:ident, $irq:ident) => { - impl sealed::Instance for peripherals::$name { + impl SealedInstance for peripherals::$name { const PIO_NO: u8 = $pio; const PIO: &'static pac::pio::Pio = &pac::$pac; const FUNCSEL: pac::io::vals::Gpio0ctrlFuncsel = pac::io::vals::Gpio0ctrlFuncsel::$funcsel; + } + impl Instance for peripherals::$name { type Interrupt = crate::interrupt::typelevel::$irq; } - impl Instance for peripherals::$name {} }; } @@ -1198,12 +1201,11 @@ impl_pio!(PIO0, 0, PIO0, PIO0_0, PIO0_IRQ_0); impl_pio!(PIO1, 1, PIO1, PIO1_0, PIO1_IRQ_0); /// PIO pin. -pub trait PioPin: sealed::PioPin + gpio::Pin {} +pub trait PioPin: gpio::Pin {} macro_rules! impl_pio_pin { ($( $pin:ident, )*) => { $( - impl sealed::PioPin for peripherals::$pin {} impl PioPin for peripherals::$pin {} )* }; diff --git a/embassy-rp/src/pwm.rs b/embassy-rp/src/pwm.rs index 5aab3ff4f..7613e4e58 100644 --- a/embassy-rp/src/pwm.rs +++ b/embassy-rp/src/pwm.rs @@ -6,8 +6,7 @@ use fixed::FixedU16; use pac::pwm::regs::{ChDiv, Intr}; use pac::pwm::vals::Divmode; -use crate::gpio::sealed::Pin as _; -use crate::gpio::{AnyPin, Pin as GpioPin}; +use crate::gpio::{AnyPin, Pin as GpioPin, SealedPin as _}; use crate::{pac, peripherals, RegExt}; /// The configuration of a PWM slice. @@ -300,12 +299,11 @@ impl<'d, T: Slice> Drop for Pwm<'d, T> { } } -mod sealed { - pub trait Slice {} -} +trait SealedSlice {} /// PWM Slice. -pub trait Slice: Peripheral

+ sealed::Slice + Sized + 'static { +#[allow(private_bounds)] +pub trait Slice: Peripheral

+ SealedSlice + Sized + 'static { /// Slice number. fn number(&self) -> u8; @@ -317,7 +315,7 @@ pub trait Slice: Peripheral

+ sealed::Slice + Sized + 'static { macro_rules! slice { ($name:ident, $num:expr) => { - impl sealed::Slice for peripherals::$name {} + impl SealedSlice for peripherals::$name {} impl Slice for peripherals::$name { fn number(&self) -> u8 { $num diff --git a/embassy-rp/src/rtc/mod.rs b/embassy-rp/src/rtc/mod.rs index c8691bdc2..2ce7ac645 100644 --- a/embassy-rp/src/rtc/mod.rs +++ b/embassy-rp/src/rtc/mod.rs @@ -188,16 +188,15 @@ pub enum RtcError { NotRunning, } -mod sealed { - pub trait Instance { - fn regs(&self) -> crate::pac::rtc::Rtc; - } +trait SealedInstance { + fn regs(&self) -> crate::pac::rtc::Rtc; } /// RTC peripheral instance. -pub trait Instance: sealed::Instance {} +#[allow(private_bounds)] +pub trait Instance: SealedInstance {} -impl sealed::Instance for crate::peripherals::RTC { +impl SealedInstance for crate::peripherals::RTC { fn regs(&self) -> crate::pac::rtc::Rtc { crate::pac::RTC } diff --git a/embassy-rp/src/spi.rs b/embassy-rp/src/spi.rs index a2a22ffe5..ef4c644ae 100644 --- a/embassy-rp/src/spi.rs +++ b/embassy-rp/src/spi.rs @@ -7,8 +7,7 @@ use embassy_hal_internal::{into_ref, PeripheralRef}; pub use embedded_hal_02::spi::{Phase, Polarity}; use crate::dma::{AnyChannel, Channel}; -use crate::gpio::sealed::Pin as _; -use crate::gpio::{AnyPin, Pin as GpioPin}; +use crate::gpio::{AnyPin, Pin as GpioPin, SealedPin as _}; use crate::{pac, peripherals, Peripheral}; /// SPI errors. @@ -443,28 +442,26 @@ impl<'d, T: Instance> Spi<'d, T, Async> { } } -mod sealed { - use super::*; +trait SealedMode {} - pub trait Mode {} +trait SealedInstance { + const TX_DREQ: u8; + const RX_DREQ: u8; - pub trait Instance { - const TX_DREQ: u8; - const RX_DREQ: u8; - - fn regs(&self) -> pac::spi::Spi; - } + fn regs(&self) -> pac::spi::Spi; } /// Mode. -pub trait Mode: sealed::Mode {} +#[allow(private_bounds)] +pub trait Mode: SealedMode {} /// SPI instance trait. -pub trait Instance: sealed::Instance {} +#[allow(private_bounds)] +pub trait Instance: SealedInstance {} macro_rules! impl_instance { ($type:ident, $irq:ident, $tx_dreq:expr, $rx_dreq:expr) => { - impl sealed::Instance for peripherals::$type { + impl SealedInstance for peripherals::$type { const TX_DREQ: u8 = $tx_dreq; const RX_DREQ: u8 = $rx_dreq; @@ -527,7 +524,7 @@ impl_pin!(PIN_29, SPI1, CsPin); macro_rules! impl_mode { ($name:ident) => { - impl sealed::Mode for $name {} + impl SealedMode for $name {} impl Mode for $name {} }; } diff --git a/embassy-rp/src/uart/mod.rs b/embassy-rp/src/uart/mod.rs index 65dcf4eb4..ee2dcb27d 100644 --- a/embassy-rp/src/uart/mod.rs +++ b/embassy-rp/src/uart/mod.rs @@ -12,8 +12,7 @@ use pac::uart::regs::Uartris; use crate::clocks::clk_peri_freq; use crate::dma::{AnyChannel, Channel}; -use crate::gpio::sealed::Pin; -use crate::gpio::AnyPin; +use crate::gpio::{AnyPin, SealedPin}; use crate::interrupt::typelevel::{Binding, Interrupt}; use crate::pac::io::vals::{Inover, Outover}; use crate::{interrupt, pac, peripherals, Peripheral, RegExt}; @@ -1107,35 +1106,26 @@ impl<'d, T: Instance, M: Mode> embedded_hal_nb::serial::Write for Uart<'d, T, M> } } -mod sealed { - use super::*; +trait SealedMode {} - pub trait Mode {} +trait SealedInstance { + const TX_DREQ: u8; + const RX_DREQ: u8; - pub trait Instance { - const TX_DREQ: u8; - const RX_DREQ: u8; + fn regs() -> pac::uart::Uart; - type Interrupt: interrupt::typelevel::Interrupt; + fn buffered_state() -> &'static buffered::State; - fn regs() -> pac::uart::Uart; - - fn buffered_state() -> &'static buffered::State; - - fn dma_state() -> &'static DmaState; - } - pub trait TxPin {} - pub trait RxPin {} - pub trait CtsPin {} - pub trait RtsPin {} + fn dma_state() -> &'static DmaState; } /// UART mode. -pub trait Mode: sealed::Mode {} +#[allow(private_bounds)] +pub trait Mode: SealedMode {} macro_rules! impl_mode { ($name:ident) => { - impl sealed::Mode for $name {} + impl SealedMode for $name {} impl Mode for $name {} }; } @@ -1149,16 +1139,18 @@ impl_mode!(Blocking); impl_mode!(Async); /// UART instance. -pub trait Instance: sealed::Instance {} +#[allow(private_bounds)] +pub trait Instance: SealedInstance { + /// Interrupt for this instance. + type Interrupt: interrupt::typelevel::Interrupt; +} macro_rules! impl_instance { ($inst:ident, $irq:ident, $tx_dreq:expr, $rx_dreq:expr) => { - impl sealed::Instance for peripherals::$inst { + impl SealedInstance for peripherals::$inst { const TX_DREQ: u8 = $tx_dreq; const RX_DREQ: u8 = $rx_dreq; - type Interrupt = crate::interrupt::typelevel::$irq; - fn regs() -> pac::uart::Uart { pac::$inst } @@ -1176,7 +1168,9 @@ macro_rules! impl_instance { &STATE } } - impl Instance for peripherals::$inst {} + impl Instance for peripherals::$inst { + type Interrupt = crate::interrupt::typelevel::$irq; + } }; } @@ -1184,17 +1178,16 @@ impl_instance!(UART0, UART0_IRQ, 20, 21); impl_instance!(UART1, UART1_IRQ, 22, 23); /// Trait for TX pins. -pub trait TxPin: sealed::TxPin + crate::gpio::Pin {} +pub trait TxPin: crate::gpio::Pin {} /// Trait for RX pins. -pub trait RxPin: sealed::RxPin + crate::gpio::Pin {} +pub trait RxPin: crate::gpio::Pin {} /// Trait for Clear To Send (CTS) pins. -pub trait CtsPin: sealed::CtsPin + crate::gpio::Pin {} +pub trait CtsPin: crate::gpio::Pin {} /// Trait for Request To Send (RTS) pins. -pub trait RtsPin: sealed::RtsPin + crate::gpio::Pin {} +pub trait RtsPin: crate::gpio::Pin {} macro_rules! impl_pin { ($pin:ident, $instance:ident, $function:ident) => { - impl sealed::$function for peripherals::$pin {} impl $function for peripherals::$pin {} }; } diff --git a/embassy-rp/src/usb.rs b/embassy-rp/src/usb.rs index d68dee4a3..37d37d6d9 100644 --- a/embassy-rp/src/usb.rs +++ b/embassy-rp/src/usb.rs @@ -14,20 +14,19 @@ use embassy_usb_driver::{ use crate::interrupt::typelevel::{Binding, Interrupt}; use crate::{interrupt, pac, peripherals, Peripheral, RegExt}; -pub(crate) mod sealed { - pub trait Instance { - fn regs() -> crate::pac::usb::Usb; - fn dpram() -> crate::pac::usb_dpram::UsbDpram; - } +trait SealedInstance { + fn regs() -> crate::pac::usb::Usb; + fn dpram() -> crate::pac::usb_dpram::UsbDpram; } /// USB peripheral instance. -pub trait Instance: sealed::Instance + 'static { +#[allow(private_bounds)] +pub trait Instance: SealedInstance + 'static { /// Interrupt for this peripheral. type Interrupt: interrupt::typelevel::Interrupt; } -impl crate::usb::sealed::Instance for peripherals::USB { +impl crate::usb::SealedInstance for peripherals::USB { fn regs() -> pac::usb::Usb { pac::USBCTRL_REGS } diff --git a/examples/rp/src/bin/pio_stepper.rs b/examples/rp/src/bin/pio_stepper.rs index ab9ecf623..4952f4fbd 100644 --- a/examples/rp/src/bin/pio_stepper.rs +++ b/examples/rp/src/bin/pio_stepper.rs @@ -69,7 +69,7 @@ impl<'d, T: Instance, const SM: usize> PioStepper<'d, T, SM> { let clock_divider: FixedU32 = (125_000_000 / (freq * 136)).to_fixed(); assert!(clock_divider <= 65536, "clkdiv must be <= 65536"); assert!(clock_divider >= 1, "clkdiv must be >= 1"); - T::PIO.sm(SM).clkdiv().write(|w| w.0 = clock_divider.to_bits() << 8); + self.sm.set_clock_divider(clock_divider); self.sm.clkdiv_restart(); }