diff --git a/embassy-cortex-m/src/interrupt.rs b/embassy-cortex-m/src/interrupt.rs index 715f00381..7358caa46 100644 --- a/embassy-cortex-m/src/interrupt.rs +++ b/embassy-cortex-m/src/interrupt.rs @@ -3,7 +3,7 @@ use core::{mem, ptr}; use atomic_polyfill::{compiler_fence, AtomicPtr, Ordering}; use cortex_m::peripheral::NVIC; -use embassy_hal_common::Unborrow; +use embassy_hal_common::Peripheral; pub use embassy_macros::cortex_m_interrupt_take as take; /// Implementation detail, do not use outside embassy crates. @@ -32,7 +32,7 @@ unsafe impl cortex_m::interrupt::InterruptNumber for NrWrap { /// Represents an interrupt type that can be configured by embassy to handle /// interrupts. -pub unsafe trait Interrupt: Unborrow { +pub unsafe trait Interrupt: Peripheral

{ /// Return the NVIC interrupt number for this interrupt. fn number(&self) -> u16; /// Steal an instance of this interrupt diff --git a/embassy-cortex-m/src/peripheral.rs b/embassy-cortex-m/src/peripheral.rs index 6a03bfb9f..e2f295579 100644 --- a/embassy-cortex-m/src/peripheral.rs +++ b/embassy-cortex-m/src/peripheral.rs @@ -1,9 +1,9 @@ //! Peripheral interrupt handling specific to cortex-m devices. -use core::marker::PhantomData; use core::mem::MaybeUninit; use cortex_m::peripheral::scb::VectActive; use cortex_m::peripheral::{NVIC, SCB}; +use embassy_hal_common::{into_ref, Peripheral, PeripheralRef}; use crate::interrupt::{Interrupt, InterruptExt, Priority}; @@ -33,8 +33,7 @@ impl StateStorage { /// a safe way. pub struct PeripheralMutex<'a, S: PeripheralState> { state: *mut S, - _phantom: PhantomData<&'a mut S>, - irq: S::Interrupt, + irq: PeripheralRef<'a, S::Interrupt>, } /// Whether `irq` can be preempted by the current interrupt. @@ -62,8 +61,14 @@ impl<'a, S: PeripheralState> PeripheralMutex<'a, S> { /// Create a new `PeripheralMutex` wrapping `irq`, with `init` initializing the initial state. /// /// Registers `on_interrupt` as the `irq`'s handler, and enables it. - pub fn new(irq: S::Interrupt, storage: &'a mut StateStorage, init: impl FnOnce() -> S) -> Self { - if can_be_preempted(&irq) { + pub fn new( + irq: impl Peripheral

+ 'a, + storage: &'a mut StateStorage, + init: impl FnOnce() -> S, + ) -> Self { + into_ref!(irq); + + if can_be_preempted(&*irq) { panic!( "`PeripheralMutex` cannot be created in an interrupt with higher priority than the interrupt it wraps" ); @@ -88,11 +93,7 @@ impl<'a, S: PeripheralState> PeripheralMutex<'a, S> { irq.set_handler_context(state_ptr as *mut ()); irq.enable(); - Self { - irq, - state: state_ptr, - _phantom: PhantomData, - } + Self { irq, state: state_ptr } } /// Access the peripheral state ensuring interrupts are disabled so that the state can be diff --git a/embassy-hal-common/src/lib.rs b/embassy-hal-common/src/lib.rs index c8cf1c4cd..d3d9e0a84 100644 --- a/embassy-hal-common/src/lib.rs +++ b/embassy-hal-common/src/lib.rs @@ -6,10 +6,10 @@ pub(crate) mod fmt; pub mod drop; mod macros; +mod peripheral; pub mod ratio; pub mod ring_buffer; -mod unborrow; -pub use unborrow::Unborrow; +pub use peripheral::{Peripheral, PeripheralRef}; /// Low power blocking wait loop using WFE/SEV. pub fn low_power_wait_until(mut condition: impl FnMut() -> bool) { diff --git a/embassy-hal-common/src/macros.rs b/embassy-hal-common/src/macros.rs index ffa5e4fb6..7af85f782 100644 --- a/embassy-hal-common/src/macros.rs +++ b/embassy-hal-common/src/macros.rs @@ -21,13 +21,7 @@ macro_rules! peripherals { } $(#[$cfg])? - unsafe impl $crate::Unborrow for $name { - type Target = $name; - #[inline] - unsafe fn unborrow(self) -> $name { - self - } - } + $crate::impl_peripheral!($name); )* } @@ -77,22 +71,23 @@ macro_rules! peripherals { } #[macro_export] -macro_rules! unborrow { +macro_rules! into_ref { ($($name:ident),*) => { $( - let mut $name = unsafe { $name.unborrow() }; + let mut $name = $name.into_ref(); )* } } #[macro_export] -macro_rules! unsafe_impl_unborrow { +macro_rules! impl_peripheral { ($type:ident) => { - unsafe impl $crate::Unborrow for $type { - type Target = $type; + impl $crate::Peripheral for $type { + type P = $type; + #[inline] - unsafe fn unborrow(self) -> Self::Target { - self + unsafe fn clone_unchecked(&mut self) -> Self::P { + $type { ..*self } } } }; diff --git a/embassy-hal-common/src/peripheral.rs b/embassy-hal-common/src/peripheral.rs new file mode 100644 index 000000000..038cebb5e --- /dev/null +++ b/embassy-hal-common/src/peripheral.rs @@ -0,0 +1,173 @@ +use core::marker::PhantomData; +use core::ops::{Deref, DerefMut}; + +/// An exclusive reference to a peripheral. +/// +/// This is functionally the same as a `&'a mut T`. The reason for having a +/// dedicated struct is memory efficiency: +/// +/// Peripheral singletons are typically either zero-sized (for concrete peripehrals +/// like `PA9` or `Spi4`) or very small (for example `AnyPin` which is 1 byte). +/// However `&mut T` is always 4 bytes for 32-bit targets, even if T is zero-sized. +/// PeripheralRef stores a copy of `T` instead, so it's the same size. +/// +/// but it is the size of `T` not the size +/// of a pointer. This is useful if T is a zero sized type. +pub struct PeripheralRef<'a, T> { + inner: T, + _lifetime: PhantomData<&'a mut T>, +} + +impl<'a, T> PeripheralRef<'a, T> { + #[inline] + pub fn new(inner: T) -> Self { + Self { + inner, + _lifetime: PhantomData, + } + } + + /// Unsafely clone (duplicate) a peripheral singleton. + /// + /// # Safety + /// + /// This returns an owned clone of the peripheral. You must manually ensure + /// only one copy of the peripheral is in use at a time. For example, don't + /// create two SPI drivers on `SPI1`, because they will "fight" each other. + /// + /// You should strongly prefer using `reborrow()` instead. It returns a + /// `PeripheralRef` that borrows `self`, which allows the borrow checker + /// to enforce this at compile time. + pub unsafe fn clone_unchecked(&mut self) -> PeripheralRef<'a, T> + where + T: Peripheral

, + { + PeripheralRef::new(self.inner.clone_unchecked()) + } + + /// Reborrow into a "child" PeripheralRef. + /// + /// `self` will stay borrowed until the child PeripheralRef is dropped. + pub fn reborrow(&mut self) -> PeripheralRef<'_, T> + where + T: Peripheral

, + { + // safety: we're returning the clone inside a new PeripheralRef that borrows + // self, so user code can't use both at the same time. + PeripheralRef::new(unsafe { self.inner.clone_unchecked() }) + } + + /// Map the inner peripheral using `Into`. + /// + /// This converts from `PeripheralRef<'a, T>` to `PeripheralRef<'a, U>`, using an + /// `Into` impl to convert from `T` to `U`. + /// + /// For example, this can be useful to degrade GPIO pins: converting from PeripheralRef<'a, PB11>` to `PeripheralRef<'a, AnyPin>`. + #[inline] + pub fn map_into(self) -> PeripheralRef<'a, U> + where + T: Into, + { + PeripheralRef { + inner: self.inner.into(), + _lifetime: PhantomData, + } + } +} + +impl<'a, T> Deref for PeripheralRef<'a, T> { + type Target = T; + + #[inline] + fn deref(&self) -> &Self::Target { + &self.inner + } +} + +impl<'a, T> DerefMut for PeripheralRef<'a, T> { + #[inline] + fn deref_mut(&mut self) -> &mut Self::Target { + &mut self.inner + } +} + +/// Trait for any type that can be used as a peripheral of type `P`. +/// +/// This is used in driver constructors, to allow passing either owned peripherals (e.g. `TWISPI0`), +/// or borrowed peripherals (e.g. `&mut TWISPI0`). +/// +/// For example, if you have a driver with a constructor like this: +/// +/// ```ignore +/// impl<'d, T: Instance> Twim<'d, T> { +/// pub fn new( +/// twim: impl Peripheral

+ 'd, +/// irq: impl Peripheral

+ 'd, +/// sda: impl Peripheral

+ 'd, +/// scl: impl Peripheral

+ 'd, +/// config: Config, +/// ) -> Self { .. } +/// } +/// ``` +/// +/// You may call it with owned peripherals, which yields an instance that can live forever (`'static`): +/// +/// ```ignore +/// let mut twi: Twim<'static, ...> = Twim::new(p.TWISPI0, irq, p.P0_03, p.P0_04, config); +/// ``` +/// +/// Or you may call it with borrowed peripherals, which yields an instance that can only live for as long +/// as the borrows last: +/// +/// ```ignore +/// let mut twi: Twim<'_, ...> = Twim::new(&mut p.TWISPI0, &mut irq, &mut p.P0_03, &mut p.P0_04, config); +/// ``` +/// +/// # Implementation details, for HAL authors +/// +/// When writing a HAL, the intended way to use this trait is to take `impl Peripheral

` in +/// the HAL's public API (such as driver constructors), calling `.into_ref()` to obtain a `PeripheralRef`, +/// and storing that in the driver struct. +/// +/// `.into_ref()` on an owned `T` yields a `PeripheralRef<'static, T>`. +/// `.into_ref()` on an `&'a mut T` yields a `PeripheralRef<'a, T>`. +pub trait Peripheral: Sized { + /// Peripheral singleton type + type P; + + /// Unsafely clone (duplicate) a peripheral singleton. + /// + /// # Safety + /// + /// This returns an owned clone of the peripheral. You must manually ensure + /// only one copy of the peripheral is in use at a time. For example, don't + /// create two SPI drivers on `SPI1`, because they will "fight" each other. + /// + /// You should strongly prefer using `into_ref()` instead. It returns a + /// `PeripheralRef`, which allows the borrow checker to enforce this at compile time. + unsafe fn clone_unchecked(&mut self) -> Self::P; + + /// Convert a value into a `PeripheralRef`. + /// + /// When called on an owned `T`, yields a `PeripheralRef<'static, T>`. + /// When called on an `&'a mut T`, yields a `PeripheralRef<'a, T>`. + #[inline] + fn into_ref<'a>(mut self) -> PeripheralRef<'a, Self::P> + where + Self: 'a, + { + PeripheralRef::new(unsafe { self.clone_unchecked() }) + } +} + +impl<'b, T: DerefMut> Peripheral for T +where + T::Target: Peripheral, +{ + type P = ::P; + + #[inline] + unsafe fn clone_unchecked(&mut self) -> Self::P { + self.deref_mut().clone_unchecked() + } +} diff --git a/embassy-hal-common/src/unborrow.rs b/embassy-hal-common/src/unborrow.rs deleted file mode 100644 index dacfa3d42..000000000 --- a/embassy-hal-common/src/unborrow.rs +++ /dev/null @@ -1,60 +0,0 @@ -/// Unsafely unborrow an owned singleton out of a `&mut`. -/// -/// It is intended to be implemented for owned peripheral singletons, such as `USART3` or `AnyPin`. -/// Unborrowing an owned `T` yields the same `T`. Unborrowing a `&mut T` yields a copy of the T. -/// -/// This allows writing HAL drivers that either own or borrow their peripherals, but that don't have -/// to store pointers in the borrowed case. -/// -/// Safety: this trait can be used to copy non-Copy types. Implementors must not cause -/// immediate UB when copied, and must not cause UB when copies are later used, provided they -/// are only used according the [`Self::unborrow`] safety contract. -/// -pub unsafe trait Unborrow { - /// Unborrow result type - type Target; - - /// Unborrow a value. - /// - /// Safety: This returns a copy of a singleton that's normally not - /// copiable. The returned copy must ONLY be used while the lifetime of `self` is - /// valid, as if it were accessed through `self` every time. - unsafe fn unborrow(self) -> Self::Target; -} - -unsafe impl<'a, T: Unborrow> Unborrow for &'a mut T { - type Target = T::Target; - unsafe fn unborrow(self) -> Self::Target { - T::unborrow(core::ptr::read(self)) - } -} - -macro_rules! unsafe_impl_unborrow_tuples { - ($($t:ident),+) => { - unsafe impl<$($t),+> Unborrow for ($($t),+) - where - $( - $t: Unborrow - ),+ - { - type Target = ($($t),+); - unsafe fn unborrow(self) -> Self::Target { - self - } - } - - - }; -} - -unsafe_impl_unborrow_tuples!(A, B); -unsafe_impl_unborrow_tuples!(A, B, C); -unsafe_impl_unborrow_tuples!(A, B, C, D); -unsafe_impl_unborrow_tuples!(A, B, C, D, E); -unsafe_impl_unborrow_tuples!(A, B, C, D, E, F); -unsafe_impl_unborrow_tuples!(A, B, C, D, E, F, G); -unsafe_impl_unborrow_tuples!(A, B, C, D, E, F, G, H); -unsafe_impl_unborrow_tuples!(A, B, C, D, E, F, G, H, I); -unsafe_impl_unborrow_tuples!(A, B, C, D, E, F, G, H, I, J); -unsafe_impl_unborrow_tuples!(A, B, C, D, E, F, G, H, I, J, K); -unsafe_impl_unborrow_tuples!(A, B, C, D, E, F, G, H, I, J, K, L); diff --git a/embassy-lora/src/stm32wl/mod.rs b/embassy-lora/src/stm32wl/mod.rs index d7d399692..b0d101b77 100644 --- a/embassy-lora/src/stm32wl/mod.rs +++ b/embassy-lora/src/stm32wl/mod.rs @@ -3,7 +3,7 @@ use core::future::Future; use core::mem::MaybeUninit; use embassy::channel::signal::Signal; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use embassy_stm32::dma::NoDma; use embassy_stm32::gpio::{AnyPin, Output}; use embassy_stm32::interrupt::{InterruptExt, SUBGHZ_RADIO}; @@ -12,7 +12,7 @@ use embassy_stm32::subghz::{ LoRaSyncWord, Ocp, PaConfig, PaSel, PacketType, RampTime, RegMode, RfFreq, SpreadingFactor as SF, StandbyClk, Status, SubGhz, TcxoMode, TcxoTrim, Timeout, TxParams, }; -use embassy_stm32::Unborrow; +use embassy_stm32::Peripheral; use lorawan_device::async_device::radio::{Bandwidth, PhyRxTx, RfConfig, RxQuality, SpreadingFactor, TxConfig}; use lorawan_device::async_device::Timings; @@ -30,37 +30,37 @@ pub struct RadioError; static IRQ: Signal<(Status, u16)> = Signal::new(); -struct StateInner<'a> { - radio: SubGhz<'a, NoDma, NoDma>, - switch: RadioSwitch<'a>, +struct StateInner<'d> { + radio: SubGhz<'d, NoDma, NoDma>, + switch: RadioSwitch<'d>, } /// External state storage for the radio state pub struct SubGhzState<'a>(MaybeUninit>); -impl<'a> SubGhzState<'a> { +impl<'d> SubGhzState<'d> { pub const fn new() -> Self { Self(MaybeUninit::uninit()) } } /// The radio peripheral keeping the radio state and owning the radio IRQ. -pub struct SubGhzRadio<'a> { - state: *mut StateInner<'a>, - _irq: SUBGHZ_RADIO, +pub struct SubGhzRadio<'d> { + state: *mut StateInner<'d>, + _irq: PeripheralRef<'d, SUBGHZ_RADIO>, } -impl<'a> SubGhzRadio<'a> { +impl<'d> SubGhzRadio<'d> { /// Create a new instance of a SubGhz radio for LoRaWAN. /// /// # Safety /// Do not leak self or futures pub unsafe fn new( - state: &'a mut SubGhzState<'a>, - radio: SubGhz<'a, NoDma, NoDma>, - switch: RadioSwitch<'a>, - irq: impl Unborrow, + state: &'d mut SubGhzState<'d>, + radio: SubGhz<'d, NoDma, NoDma>, + switch: RadioSwitch<'d>, + irq: impl Peripheral

+ 'd, ) -> Self { - unborrow!(irq); + into_ref!(irq); let mut inner = StateInner { radio, switch }; inner.radio.reset(); @@ -73,7 +73,7 @@ impl<'a> SubGhzRadio<'a> { // This is safe because we only get interrupts when configured for, so // the radio will be awaiting on the signal at this point. If not, the ISR will // anyway only adjust the state in the IRQ signal state. - let state = &mut *(p as *mut StateInner<'a>); + let state = &mut *(p as *mut StateInner<'d>); state.on_interrupt(); }); irq.set_handler_context(state_ptr as *mut ()); @@ -86,7 +86,7 @@ impl<'a> SubGhzRadio<'a> { } } -impl<'a> StateInner<'a> { +impl<'d> StateInner<'d> { /// Configure radio settings in preparation for TX or RX pub(crate) fn configure(&mut self) -> Result<(), RadioError> { trace!("Configuring STM32WL SUBGHZ radio"); @@ -272,13 +272,13 @@ impl PhyRxTx for SubGhzRadio<'static> { } } -impl<'a> From for RadioError { +impl From for RadioError { fn from(_: embassy_stm32::spi::Error) -> Self { RadioError } } -impl<'a> Timings for SubGhzRadio<'a> { +impl<'d> Timings for SubGhzRadio<'d> { fn get_rx_window_offset_ms(&self) -> i32 { -200 } @@ -288,14 +288,14 @@ impl<'a> Timings for SubGhzRadio<'a> { } /// Represents the radio switch found on STM32WL based boards, used to control the radio for transmission or reception. -pub struct RadioSwitch<'a> { - ctrl1: Output<'a, AnyPin>, - ctrl2: Output<'a, AnyPin>, - ctrl3: Output<'a, AnyPin>, +pub struct RadioSwitch<'d> { + ctrl1: Output<'d, AnyPin>, + ctrl2: Output<'d, AnyPin>, + ctrl3: Output<'d, AnyPin>, } -impl<'a> RadioSwitch<'a> { - pub fn new(ctrl1: Output<'a, AnyPin>, ctrl2: Output<'a, AnyPin>, ctrl3: Output<'a, AnyPin>) -> Self { +impl<'d> RadioSwitch<'d> { + pub fn new(ctrl1: Output<'d, AnyPin>, ctrl2: Output<'d, AnyPin>, ctrl3: Output<'d, AnyPin>) -> Self { Self { ctrl1, ctrl2, ctrl3 } } diff --git a/embassy-macros/src/macros/cortex_m_interrupt_declare.rs b/embassy-macros/src/macros/cortex_m_interrupt_declare.rs index eeed5d483..ab61ad5da 100644 --- a/embassy-macros/src/macros/cortex_m_interrupt_declare.rs +++ b/embassy-macros/src/macros/cortex_m_interrupt_declare.rs @@ -25,12 +25,7 @@ pub fn run(name: syn::Ident) -> Result { } } - unsafe impl ::embassy_hal_common::Unborrow for #name_interrupt { - type Target = #name_interrupt; - unsafe fn unborrow(self) -> #name_interrupt { - self - } - } + ::embassy_hal_common::impl_peripheral!(#name_interrupt); }; Ok(result) } diff --git a/embassy-nrf/src/buffered_uarte.rs b/embassy-nrf/src/buffered_uarte.rs index 4fc78b95d..89c1ba908 100644 --- a/embassy-nrf/src/buffered_uarte.rs +++ b/embassy-nrf/src/buffered_uarte.rs @@ -15,14 +15,13 @@ use core::cmp::min; use core::future::Future; -use core::marker::PhantomData; use core::sync::atomic::{compiler_fence, Ordering}; use core::task::Poll; use embassy::waitqueue::WakerRegistration; use embassy_cortex_m::peripheral::{PeripheralMutex, PeripheralState, StateStorage}; use embassy_hal_common::ring_buffer::RingBuffer; -use embassy_hal_common::{low_power_wait_until, unborrow}; +use embassy_hal_common::{into_ref, low_power_wait_until, PeripheralRef}; use futures::future::poll_fn; // Re-export SVD variants to allow user to directly set values pub use pac::uarte0::{baudrate::BAUDRATE_A as Baudrate, config::PARITY_A as Parity}; @@ -32,7 +31,7 @@ use crate::interrupt::InterruptExt; use crate::ppi::{AnyConfigurableChannel, ConfigurableChannel, Event, Ppi, Task}; use crate::timer::{Frequency, Instance as TimerInstance, Timer}; use crate::uarte::{apply_workaround_for_enable_anomaly, Config, Instance as UarteInstance}; -use crate::{pac, Unborrow}; +use crate::{pac, Peripheral}; #[derive(Copy, Clone, Debug, PartialEq)] enum RxState { @@ -54,7 +53,7 @@ impl<'d, U: UarteInstance, T: TimerInstance> State<'d, U, T> { } struct StateInner<'d, U: UarteInstance, T: TimerInstance> { - phantom: PhantomData<&'d mut U>, + _peri: PeripheralRef<'d, U>, timer: Timer<'d, T>, _ppi_ch1: Ppi<'d, AnyConfigurableChannel, 1, 2>, _ppi_ch2: Ppi<'d, AnyConfigurableChannel, 1, 1>, @@ -78,20 +77,20 @@ impl<'d, U: UarteInstance, T: TimerInstance> Unpin for BufferedUarte<'d, U, T> { impl<'d, U: UarteInstance, T: TimerInstance> BufferedUarte<'d, U, T> { pub fn new( state: &'d mut State<'d, U, T>, - _uarte: impl Unborrow + 'd, - timer: impl Unborrow + 'd, - ppi_ch1: impl Unborrow + 'd, - ppi_ch2: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - rxd: impl Unborrow + 'd, - txd: impl Unborrow + 'd, - cts: impl Unborrow + 'd, - rts: impl Unborrow + 'd, + peri: impl Peripheral

+ 'd, + timer: impl Peripheral

+ 'd, + ppi_ch1: impl Peripheral

+ 'd, + ppi_ch2: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + rxd: impl Peripheral

+ 'd, + txd: impl Peripheral

+ 'd, + cts: impl Peripheral

+ 'd, + rts: impl Peripheral

+ 'd, config: Config, rx_buffer: &'d mut [u8], tx_buffer: &'d mut [u8], ) -> Self { - unborrow!(ppi_ch1, ppi_ch2, irq, rxd, txd, cts, rts); + into_ref!(peri, ppi_ch1, ppi_ch2, irq, rxd, txd, cts, rts); let r = U::regs(); @@ -147,7 +146,7 @@ impl<'d, U: UarteInstance, T: TimerInstance> BufferedUarte<'d, U, T> { timer.cc(0).short_compare_stop(); let mut ppi_ch1 = Ppi::new_one_to_two( - ppi_ch1.degrade(), + ppi_ch1.map_into(), Event::from_reg(&r.events_rxdrdy), timer.task_clear(), timer.task_start(), @@ -155,7 +154,7 @@ impl<'d, U: UarteInstance, T: TimerInstance> BufferedUarte<'d, U, T> { ppi_ch1.enable(); let mut ppi_ch2 = Ppi::new_one_to_one( - ppi_ch2.degrade(), + ppi_ch2.map_into(), timer.cc(0).event_compare(), Task::from_reg(&r.tasks_stoprx), ); @@ -163,7 +162,7 @@ impl<'d, U: UarteInstance, T: TimerInstance> BufferedUarte<'d, U, T> { Self { inner: PeripheralMutex::new(irq, &mut state.0, move || StateInner { - phantom: PhantomData, + _peri: peri, timer, _ppi_ch1: ppi_ch1, _ppi_ch2: ppi_ch2, diff --git a/embassy-nrf/src/gpio.rs b/embassy-nrf/src/gpio.rs index fd4ae2ec3..a61ff6aa5 100644 --- a/embassy-nrf/src/gpio.rs +++ b/embassy-nrf/src/gpio.rs @@ -2,15 +2,14 @@ use core::convert::Infallible; use core::hint::unreachable_unchecked; -use core::marker::PhantomData; use cfg_if::cfg_if; -use embassy_hal_common::{unborrow, unsafe_impl_unborrow}; +use embassy_hal_common::{impl_peripheral, into_ref, PeripheralRef}; use self::sealed::Pin as _; use crate::pac::p0 as gpio; use crate::pac::p0::pin_cnf::{DRIVE_A, PULL_A}; -use crate::{pac, Unborrow}; +use crate::{pac, Peripheral}; /// A GPIO port with up to 32 pins. #[derive(Debug, Eq, PartialEq)] @@ -39,7 +38,7 @@ pub struct Input<'d, T: Pin> { impl<'d, T: Pin> Input<'d, T> { #[inline] - pub fn new(pin: impl Unborrow + 'd, pull: Pull) -> Self { + pub fn new(pin: impl Peripheral

+ 'd, pull: Pull) -> Self { let mut pin = Flex::new(pin); pin.set_as_input(pull); @@ -119,7 +118,7 @@ pub struct Output<'d, T: Pin> { impl<'d, T: Pin> Output<'d, T> { #[inline] - pub fn new(pin: impl Unborrow + 'd, initial_output: Level, drive: OutputDrive) -> Self { + pub fn new(pin: impl Peripheral

+ 'd, initial_output: Level, drive: OutputDrive) -> Self { let mut pin = Flex::new(pin); match initial_output { Level::High => pin.set_high(), @@ -194,8 +193,7 @@ fn convert_pull(pull: Pull) -> PULL_A { /// set while not in output mode, so the pin's level will be 'remembered' when it is not in output /// mode. pub struct Flex<'d, T: Pin> { - pub(crate) pin: T, - phantom: PhantomData<&'d mut T>, + pub(crate) pin: PeripheralRef<'d, T>, } impl<'d, T: Pin> Flex<'d, T> { @@ -204,13 +202,10 @@ impl<'d, T: Pin> Flex<'d, T> { /// The pin remains disconnected. The initial output level is unspecified, but can be changed /// before the pin is put into output mode. #[inline] - pub fn new(pin: impl Unborrow + 'd) -> Self { - unborrow!(pin); + pub fn new(pin: impl Peripheral

+ 'd) -> Self { + into_ref!(pin); // Pin will be in disconnected state. - Self { - pin, - phantom: PhantomData, - } + Self { pin } } /// Put the pin into input mode. @@ -379,7 +374,7 @@ pub(crate) mod sealed { } } -pub trait Pin: Unborrow + sealed::Pin + Sized + 'static { +pub trait Pin: Peripheral

+ Into + sealed::Pin + Sized + 'static { /// Number of the pin within the port (0..31) #[inline] fn pin(&self) -> u8 { @@ -423,7 +418,7 @@ impl AnyPin { } } -unsafe_impl_unborrow!(AnyPin); +impl_peripheral!(AnyPin); impl Pin for AnyPin {} impl sealed::Pin for AnyPin { #[inline] @@ -438,10 +433,13 @@ pub(crate) trait PselBits { fn psel_bits(&self) -> u32; } -impl PselBits for Option { +impl<'a, P: Pin> PselBits for Option> { #[inline] fn psel_bits(&self) -> u32 { - self.as_ref().map_or(1u32 << 31, Pin::psel_bits) + match self { + Some(pin) => pin.psel_bits(), + None => 1u32 << 31, + } } } @@ -463,6 +461,12 @@ macro_rules! impl_pin { $port_num * 32 + $pin_num } } + + impl From for crate::gpio::AnyPin { + fn from(val: peripherals::$type) -> Self { + crate::gpio::Pin::degrade(val) + } + } }; } diff --git a/embassy-nrf/src/gpiote.rs b/embassy-nrf/src/gpiote.rs index d4e1cb35c..cef80ae0a 100644 --- a/embassy-nrf/src/gpiote.rs +++ b/embassy-nrf/src/gpiote.rs @@ -1,10 +1,9 @@ use core::convert::Infallible; use core::future::Future; -use core::marker::PhantomData; use core::task::{Context, Poll}; use embassy::waitqueue::AtomicWaker; -use embassy_hal_common::unsafe_impl_unborrow; +use embassy_hal_common::{impl_peripheral, Peripheral, PeripheralRef}; use futures::future::poll_fn; use crate::gpio::sealed::Pin as _; @@ -301,16 +300,22 @@ impl<'d, C: Channel, T: GpioPin> OutputChannel<'d, C, T> { // ======================= pub(crate) struct PortInputFuture<'a> { - pin_port: u8, - phantom: PhantomData<&'a mut AnyPin>, + pin: PeripheralRef<'a, AnyPin>, +} + +impl<'a> PortInputFuture<'a> { + fn new(pin: impl Peripheral

+ 'a) -> Self { + Self { + pin: pin.into_ref().map_into(), + } + } } impl<'a> Unpin for PortInputFuture<'a> {} impl<'a> Drop for PortInputFuture<'a> { fn drop(&mut self) { - let pin = unsafe { AnyPin::steal(self.pin_port) }; - pin.conf().modify(|_, w| w.sense().disabled()); + self.pin.conf().modify(|_, w| w.sense().disabled()); } } @@ -318,10 +323,9 @@ impl<'a> Future for PortInputFuture<'a> { type Output = (); fn poll(self: core::pin::Pin<&mut Self>, cx: &mut Context<'_>) -> Poll { - PORT_WAKERS[self.pin_port as usize].register(cx.waker()); + PORT_WAKERS[self.pin.pin_port() as usize].register(cx.waker()); - let pin = unsafe { AnyPin::steal(self.pin_port) }; - if pin.conf().read().sense().is_disabled() { + if self.pin.conf().read().sense().is_disabled() { Poll::Ready(()) } else { Poll::Pending @@ -354,22 +358,12 @@ impl<'d, T: GpioPin> Input<'d, T> { impl<'d, T: GpioPin> Flex<'d, T> { pub async fn wait_for_high(&mut self) { self.pin.conf().modify(|_, w| w.sense().high()); - - PortInputFuture { - pin_port: self.pin.pin_port(), - phantom: PhantomData, - } - .await + PortInputFuture::new(&mut self.pin).await } pub async fn wait_for_low(&mut self) { self.pin.conf().modify(|_, w| w.sense().low()); - - PortInputFuture { - pin_port: self.pin.pin_port(), - phantom: PhantomData, - } - .await + PortInputFuture::new(&mut self.pin).await } pub async fn wait_for_rising_edge(&mut self) { @@ -388,11 +382,7 @@ impl<'d, T: GpioPin> Flex<'d, T> { } else { self.pin.conf().modify(|_, w| w.sense().high()); } - PortInputFuture { - pin_port: self.pin.pin_port(), - phantom: PhantomData, - } - .await + PortInputFuture::new(&mut self.pin).await } } @@ -414,7 +404,7 @@ pub trait Channel: sealed::Channel + Sized { pub struct AnyChannel { number: u8, } -unsafe_impl_unborrow!(AnyChannel); +impl_peripheral!(AnyChannel); impl sealed::Channel for AnyChannel {} impl Channel for AnyChannel { fn number(&self) -> usize { diff --git a/embassy-nrf/src/lib.rs b/embassy-nrf/src/lib.rs index 3699ad0fa..ad6c16c1f 100644 --- a/embassy-nrf/src/lib.rs +++ b/embassy-nrf/src/lib.rs @@ -135,7 +135,7 @@ pub use chip::pac; pub(crate) use chip::pac; pub use chip::{peripherals, Peripherals}; pub use embassy_cortex_m::executor; -pub use embassy_hal_common::{unborrow, Unborrow}; +pub use embassy_hal_common::{into_ref, Peripheral, PeripheralRef}; pub use embassy_macros::cortex_m_interrupt as interrupt; pub mod config { diff --git a/embassy-nrf/src/nvmc.rs b/embassy-nrf/src/nvmc.rs index e350f8c99..cd6100339 100644 --- a/embassy-nrf/src/nvmc.rs +++ b/embassy-nrf/src/nvmc.rs @@ -1,15 +1,14 @@ //! Nvmcerature sensor interface. -use core::marker::PhantomData; use core::{ptr, slice}; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use embedded_storage::nor_flash::{ ErrorType, MultiwriteNorFlash, NorFlash, NorFlashError, NorFlashErrorKind, ReadNorFlash, }; use crate::peripherals::NVMC; -use crate::{pac, Unborrow}; +use crate::{pac, Peripheral}; pub const PAGE_SIZE: usize = 4096; pub const FLASH_SIZE: usize = crate::chip::FLASH_SIZE; @@ -31,14 +30,13 @@ impl NorFlashError for Error { } pub struct Nvmc<'d> { - _p: PhantomData<&'d NVMC>, + _p: PeripheralRef<'d, NVMC>, } impl<'d> Nvmc<'d> { - pub fn new(_p: impl Unborrow + 'd) -> Self { - unborrow!(_p); - - Self { _p: PhantomData } + pub fn new(_p: impl Peripheral

+ 'd) -> Self { + into_ref!(_p); + Self { _p } } fn regs() -> &'static pac::nvmc::RegisterBlock { diff --git a/embassy-nrf/src/ppi/dppi.rs b/embassy-nrf/src/ppi/dppi.rs index d0bffb1e0..de856c0ca 100644 --- a/embassy-nrf/src/ppi/dppi.rs +++ b/embassy-nrf/src/ppi/dppi.rs @@ -1,9 +1,7 @@ -use core::marker::PhantomData; - -use embassy_hal_common::unborrow; +use embassy_hal_common::into_ref; use super::{Channel, ConfigurableChannel, Event, Ppi, Task}; -use crate::{pac, Unborrow}; +use crate::{pac, Peripheral}; const DPPI_ENABLE_BIT: u32 = 0x8000_0000; const DPPI_CHANNEL_MASK: u32 = 0x0000_00FF; @@ -13,13 +11,13 @@ fn regs() -> &'static pac::dppic::RegisterBlock { } impl<'d, C: ConfigurableChannel> Ppi<'d, C, 1, 1> { - pub fn new_one_to_one(ch: impl Unborrow + 'd, event: Event, task: Task) -> Self { + pub fn new_one_to_one(ch: impl Peripheral

+ 'd, event: Event, task: Task) -> Self { Ppi::new_many_to_many(ch, [event], [task]) } } impl<'d, C: ConfigurableChannel> Ppi<'d, C, 1, 2> { - pub fn new_one_to_two(ch: impl Unborrow + 'd, event: Event, task1: Task, task2: Task) -> Self { + pub fn new_one_to_two(ch: impl Peripheral

+ 'd, event: Event, task1: Task, task2: Task) -> Self { Ppi::new_many_to_many(ch, [event], [task1, task2]) } } @@ -28,11 +26,11 @@ impl<'d, C: ConfigurableChannel, const EVENT_COUNT: usize, const TASK_COUNT: usi Ppi<'d, C, EVENT_COUNT, TASK_COUNT> { pub fn new_many_to_many( - ch: impl Unborrow + 'd, + ch: impl Peripheral

+ 'd, events: [Event; EVENT_COUNT], tasks: [Task; TASK_COUNT], ) -> Self { - unborrow!(ch); + into_ref!(ch); let val = DPPI_ENABLE_BIT | (ch.number() as u32 & DPPI_CHANNEL_MASK); for task in tasks { @@ -48,12 +46,7 @@ impl<'d, C: ConfigurableChannel, const EVENT_COUNT: usize, const TASK_COUNT: usi unsafe { event.publish_reg().write_volatile(val) } } - Self { - ch, - events, - tasks, - phantom: PhantomData, - } + Self { ch, events, tasks } } } diff --git a/embassy-nrf/src/ppi/mod.rs b/embassy-nrf/src/ppi/mod.rs index 660db6410..23ab011bc 100644 --- a/embassy-nrf/src/ppi/mod.rs +++ b/embassy-nrf/src/ppi/mod.rs @@ -15,12 +15,11 @@ //! many tasks and events, but any single task or event can only be coupled with one channel. //! -use core::marker::PhantomData; use core::ptr::NonNull; -use embassy_hal_common::unsafe_impl_unborrow; +use embassy_hal_common::{impl_peripheral, PeripheralRef}; -use crate::{peripherals, Unborrow}; +use crate::{peripherals, Peripheral}; #[cfg(feature = "_dppi")] mod dppi; @@ -28,12 +27,11 @@ mod dppi; mod ppi; pub struct Ppi<'d, C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize> { - ch: C, + ch: PeripheralRef<'d, C>, #[cfg(feature = "_dppi")] events: [Event; EVENT_COUNT], #[cfg(feature = "_dppi")] tasks: [Task; TASK_COUNT], - phantom: PhantomData<&'d mut C>, } const REGISTER_DPPI_CONFIG_OFFSET: usize = 0x80 / core::mem::size_of::(); @@ -89,16 +87,16 @@ pub(crate) mod sealed { pub trait Group {} } -pub trait Channel: sealed::Channel + Unborrow + Sized { +pub trait Channel: sealed::Channel + Peripheral

+ Sized { /// Returns the number of the channel fn number(&self) -> usize; } -pub trait ConfigurableChannel: Channel { +pub trait ConfigurableChannel: Channel + Into { fn degrade(self) -> AnyConfigurableChannel; } -pub trait StaticChannel: Channel { +pub trait StaticChannel: Channel + Into { fn degrade(self) -> AnyStaticChannel; } @@ -119,7 +117,7 @@ pub trait Group: sealed::Group + Sized { pub struct AnyStaticChannel { pub(crate) number: u8, } -unsafe_impl_unborrow!(AnyStaticChannel); +impl_peripheral!(AnyStaticChannel); impl sealed::Channel for AnyStaticChannel {} impl Channel for AnyStaticChannel { fn number(&self) -> usize { @@ -137,7 +135,7 @@ impl StaticChannel for AnyStaticChannel { pub struct AnyConfigurableChannel { pub(crate) number: u8, } -unsafe_impl_unborrow!(AnyConfigurableChannel); +impl_peripheral!(AnyConfigurableChannel); impl sealed::Channel for AnyConfigurableChannel {} impl Channel for AnyConfigurableChannel { fn number(&self) -> usize { @@ -169,6 +167,12 @@ macro_rules! impl_ppi_channel { } } } + + impl From for crate::ppi::AnyStaticChannel { + fn from(val: peripherals::$type) -> Self { + crate::ppi::StaticChannel::degrade(val) + } + } }; ($type:ident, $number:expr => configurable) => { impl_ppi_channel!($type, $number); @@ -180,6 +184,12 @@ macro_rules! impl_ppi_channel { } } } + + impl From for crate::ppi::AnyConfigurableChannel { + fn from(val: peripherals::$type) -> Self { + crate::ppi::ConfigurableChannel::degrade(val) + } + } }; } @@ -189,7 +199,7 @@ macro_rules! impl_ppi_channel { pub struct AnyGroup { number: u8, } -unsafe_impl_unborrow!(AnyGroup); +impl_peripheral!(AnyGroup); impl sealed::Group for AnyGroup {} impl Group for AnyGroup { fn number(&self) -> usize { diff --git a/embassy-nrf/src/ppi/ppi.rs b/embassy-nrf/src/ppi/ppi.rs index e5c86d444..450a290a2 100644 --- a/embassy-nrf/src/ppi/ppi.rs +++ b/embassy-nrf/src/ppi/ppi.rs @@ -1,9 +1,7 @@ -use core::marker::PhantomData; - -use embassy_hal_common::unborrow; +use embassy_hal_common::into_ref; use super::{Channel, ConfigurableChannel, Event, Ppi, StaticChannel, Task}; -use crate::{pac, Unborrow}; +use crate::{pac, Peripheral}; impl Task { fn reg_val(&self) -> u32 { @@ -22,40 +20,34 @@ 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> { - pub fn new_zero_to_one(ch: impl Unborrow + 'd, task: Task) -> Self { - unborrow!(ch); + pub fn new_zero_to_one(ch: impl Peripheral

+ 'd, task: Task) -> Self { + into_ref!(ch); let r = regs(); let n = ch.number(); r.fork[n].tep.write(|w| unsafe { w.bits(task.reg_val()) }); - Self { - ch, - phantom: PhantomData, - } + Self { ch } } } impl<'d, C: ConfigurableChannel> Ppi<'d, C, 1, 1> { - pub fn new_one_to_one(ch: impl Unborrow + 'd, event: Event, task: Task) -> Self { - unborrow!(ch); + pub fn new_one_to_one(ch: impl Peripheral

+ 'd, event: Event, task: Task) -> Self { + into_ref!(ch); let r = regs(); let n = ch.number(); r.ch[n].eep.write(|w| unsafe { w.bits(event.reg_val()) }); r.ch[n].tep.write(|w| unsafe { w.bits(task.reg_val()) }); - Self { - ch, - phantom: PhantomData, - } + Self { ch } } } #[cfg(not(feature = "nrf51"))] // Not for nrf51 because of the fork task impl<'d, C: ConfigurableChannel> Ppi<'d, C, 1, 2> { - pub fn new_one_to_two(ch: impl Unborrow + 'd, event: Event, task1: Task, task2: Task) -> Self { - unborrow!(ch); + pub fn new_one_to_two(ch: impl Peripheral

+ 'd, event: Event, task1: Task, task2: Task) -> Self { + into_ref!(ch); let r = regs(); let n = ch.number(); @@ -63,10 +55,7 @@ impl<'d, C: ConfigurableChannel> Ppi<'d, C, 1, 2> { r.ch[n].tep.write(|w| unsafe { w.bits(task1.reg_val()) }); r.fork[n].tep.write(|w| unsafe { w.bits(task2.reg_val()) }); - Self { - ch, - phantom: PhantomData, - } + Self { ch } } } diff --git a/embassy-nrf/src/pwm.rs b/embassy-nrf/src/pwm.rs index 9a78ff1f1..5f750a91e 100644 --- a/embassy-nrf/src/pwm.rs +++ b/embassy-nrf/src/pwm.rs @@ -1,36 +1,35 @@ #![macro_use] -use core::marker::PhantomData; use core::sync::atomic::{compiler_fence, Ordering}; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use crate::gpio::sealed::Pin as _; use crate::gpio::{AnyPin, Pin as GpioPin, PselBits}; use crate::interrupt::Interrupt; use crate::ppi::{Event, Task}; use crate::util::slice_in_ram_or; -use crate::{pac, Unborrow}; +use crate::{pac, Peripheral}; /// SimplePwm is the traditional pwm interface you're probably used to, allowing /// to simply set a duty cycle across up to four channels. pub struct SimplePwm<'d, T: Instance> { - phantom: PhantomData<&'d mut T>, + _peri: PeripheralRef<'d, T>, duty: [u16; 4], - ch0: Option, - ch1: Option, - ch2: Option, - ch3: Option, + ch0: Option>, + ch1: Option>, + ch2: Option>, + ch3: Option>, } /// SequencePwm allows you to offload the updating of a sequence of duty cycles /// to up to four channels, as well as repeat that sequence n times. pub struct SequencePwm<'d, T: Instance> { - phantom: PhantomData<&'d mut T>, - ch0: Option, - ch1: Option, - ch2: Option, - ch3: Option, + _peri: PeripheralRef<'d, T>, + ch0: Option>, + ch1: Option>, + ch2: Option>, + ch3: Option>, } #[derive(Debug, Clone, Copy, PartialEq, Eq)] @@ -51,41 +50,41 @@ impl<'d, T: Instance> SequencePwm<'d, T> { /// Create a new 1-channel PWM #[allow(unused_unsafe)] pub fn new_1ch( - pwm: impl Unborrow + 'd, - ch0: impl Unborrow + 'd, + pwm: impl Peripheral

+ 'd, + ch0: impl Peripheral

+ 'd, config: Config, ) -> Result { - unborrow!(ch0); - Self::new_inner(pwm, Some(ch0.degrade()), None, None, None, config) + into_ref!(ch0); + Self::new_inner(pwm, Some(ch0.map_into()), None, None, None, config) } /// Create a new 2-channel PWM #[allow(unused_unsafe)] pub fn new_2ch( - pwm: impl Unborrow + 'd, - ch0: impl Unborrow + 'd, - ch1: impl Unborrow + 'd, + pwm: impl Peripheral

+ 'd, + ch0: impl Peripheral

+ 'd, + ch1: impl Peripheral

+ 'd, config: Config, ) -> Result { - unborrow!(ch0, ch1); - Self::new_inner(pwm, Some(ch0.degrade()), Some(ch1.degrade()), None, None, config) + into_ref!(ch0, ch1); + Self::new_inner(pwm, Some(ch0.map_into()), Some(ch1.map_into()), None, None, config) } /// Create a new 3-channel PWM #[allow(unused_unsafe)] pub fn new_3ch( - pwm: impl Unborrow + 'd, - ch0: impl Unborrow + 'd, - ch1: impl Unborrow + 'd, - ch2: impl Unborrow + 'd, + pwm: impl Peripheral

+ 'd, + ch0: impl Peripheral

+ 'd, + ch1: impl Peripheral

+ 'd, + ch2: impl Peripheral

+ 'd, config: Config, ) -> Result { - unborrow!(ch0, ch1, ch2); + into_ref!(ch0, ch1, ch2); Self::new_inner( pwm, - Some(ch0.degrade()), - Some(ch1.degrade()), - Some(ch2.degrade()), + Some(ch0.map_into()), + Some(ch1.map_into()), + Some(ch2.map_into()), None, config, ) @@ -94,32 +93,34 @@ impl<'d, T: Instance> SequencePwm<'d, T> { /// Create a new 4-channel PWM #[allow(unused_unsafe)] pub fn new_4ch( - pwm: impl Unborrow + 'd, - ch0: impl Unborrow + 'd, - ch1: impl Unborrow + 'd, - ch2: impl Unborrow + 'd, - ch3: impl Unborrow + 'd, + pwm: impl Peripheral

+ 'd, + ch0: impl Peripheral

+ 'd, + ch1: impl Peripheral

+ 'd, + ch2: impl Peripheral

+ 'd, + ch3: impl Peripheral

+ 'd, config: Config, ) -> Result { - unborrow!(ch0, ch1, ch2, ch3); + into_ref!(ch0, ch1, ch2, ch3); Self::new_inner( pwm, - Some(ch0.degrade()), - Some(ch1.degrade()), - Some(ch2.degrade()), - Some(ch3.degrade()), + Some(ch0.map_into()), + Some(ch1.map_into()), + Some(ch2.map_into()), + Some(ch3.map_into()), config, ) } fn new_inner( - _pwm: impl Unborrow + 'd, - ch0: Option, - ch1: Option, - ch2: Option, - ch3: Option, + _pwm: impl Peripheral

+ 'd, + ch0: Option>, + ch1: Option>, + ch2: Option>, + ch3: Option>, config: Config, ) -> Result { + into_ref!(_pwm); + let r = T::regs(); if let Some(pin) = &ch0 { @@ -168,7 +169,7 @@ impl<'d, T: Instance> SequencePwm<'d, T> { r.countertop.write(|w| unsafe { w.countertop().bits(config.max_duty) }); Ok(Self { - phantom: PhantomData, + _peri: _pwm, ch0, ch1, ch2, @@ -573,60 +574,74 @@ pub enum CounterMode { impl<'d, T: Instance> SimplePwm<'d, T> { /// Create a new 1-channel PWM #[allow(unused_unsafe)] - pub fn new_1ch(pwm: impl Unborrow + 'd, ch0: impl Unborrow + 'd) -> Self { - unborrow!(ch0); - Self::new_inner(pwm, Some(ch0.degrade()), None, None, None) + pub fn new_1ch(pwm: impl Peripheral

+ 'd, ch0: impl Peripheral

+ 'd) -> Self { + unsafe { + into_ref!(ch0); + Self::new_inner(pwm, Some(ch0.map_into()), None, None, None) + } } /// Create a new 2-channel PWM #[allow(unused_unsafe)] pub fn new_2ch( - pwm: impl Unborrow + 'd, - ch0: impl Unborrow + 'd, - ch1: impl Unborrow + 'd, + pwm: impl Peripheral

+ 'd, + ch0: impl Peripheral

+ 'd, + ch1: impl Peripheral

+ 'd, ) -> Self { - unborrow!(ch0, ch1); - Self::new_inner(pwm, Some(ch0.degrade()), Some(ch1.degrade()), None, None) + into_ref!(ch0, ch1); + Self::new_inner(pwm, Some(ch0.map_into()), Some(ch1.map_into()), None, None) } /// Create a new 3-channel PWM #[allow(unused_unsafe)] pub fn new_3ch( - pwm: impl Unborrow + 'd, - ch0: impl Unborrow + 'd, - ch1: impl Unborrow + 'd, - ch2: impl Unborrow + 'd, + pwm: impl Peripheral

+ 'd, + ch0: impl Peripheral

+ 'd, + ch1: impl Peripheral

+ 'd, + ch2: impl Peripheral

+ 'd, ) -> Self { - unborrow!(ch0, ch1, ch2); - Self::new_inner(pwm, Some(ch0.degrade()), Some(ch1.degrade()), Some(ch2.degrade()), None) + unsafe { + into_ref!(ch0, ch1, ch2); + Self::new_inner( + pwm, + Some(ch0.map_into()), + Some(ch1.map_into()), + Some(ch2.map_into()), + None, + ) + } } /// Create a new 4-channel PWM #[allow(unused_unsafe)] pub fn new_4ch( - pwm: impl Unborrow + 'd, - ch0: impl Unborrow + 'd, - ch1: impl Unborrow + 'd, - ch2: impl Unborrow + 'd, - ch3: impl Unborrow + 'd, + pwm: impl Peripheral

+ 'd, + ch0: impl Peripheral

+ 'd, + ch1: impl Peripheral

+ 'd, + ch2: impl Peripheral

+ 'd, + ch3: impl Peripheral

+ 'd, ) -> Self { - unborrow!(ch0, ch1, ch2, ch3); - Self::new_inner( - pwm, - Some(ch0.degrade()), - Some(ch1.degrade()), - Some(ch2.degrade()), - Some(ch3.degrade()), - ) + unsafe { + into_ref!(ch0, ch1, ch2, ch3); + Self::new_inner( + pwm, + Some(ch0.map_into()), + Some(ch1.map_into()), + Some(ch2.map_into()), + Some(ch3.map_into()), + ) + } } fn new_inner( - _pwm: impl Unborrow + 'd, - ch0: Option, - ch1: Option, - ch2: Option, - ch3: Option, + _pwm: impl Peripheral

+ 'd, + ch0: Option>, + ch1: Option>, + ch2: Option>, + ch3: Option>, ) -> Self { + into_ref!(_pwm); + let r = T::regs(); if let Some(pin) = &ch0 { @@ -654,7 +669,7 @@ impl<'d, T: Instance> SimplePwm<'d, T> { r.psel.out[3].write(|w| unsafe { w.bits(ch3.psel_bits()) }); let pwm = Self { - phantom: PhantomData, + _peri: _pwm, ch0, ch1, ch2, @@ -813,7 +828,7 @@ pub(crate) mod sealed { } } -pub trait Instance: Unborrow + sealed::Instance + 'static { +pub trait Instance: Peripheral

+ sealed::Instance + 'static { type Interrupt: Interrupt; } diff --git a/embassy-nrf/src/qdec.rs b/embassy-nrf/src/qdec.rs index e254328a6..f6daec252 100644 --- a/embassy-nrf/src/qdec.rs +++ b/embassy-nrf/src/qdec.rs @@ -1,21 +1,20 @@ //! Quadrature decoder interface -use core::marker::PhantomData; use core::task::Poll; use embassy::waitqueue::AtomicWaker; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use futures::future::poll_fn; use crate::gpio::sealed::Pin as _; use crate::gpio::{AnyPin, Pin as GpioPin}; use crate::interrupt::InterruptExt; use crate::peripherals::QDEC; -use crate::{interrupt, pac, Unborrow}; +use crate::{interrupt, pac, Peripheral}; /// Quadrature decoder pub struct Qdec<'d> { - phantom: PhantomData<&'d QDEC>, + _p: PeripheralRef<'d, QDEC>, } #[non_exhaustive] @@ -43,37 +42,37 @@ static WAKER: AtomicWaker = AtomicWaker::new(); impl<'d> Qdec<'d> { pub fn new( - qdec: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - a: impl Unborrow + 'd, - b: impl Unborrow + 'd, + qdec: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + a: impl Peripheral

+ 'd, + b: impl Peripheral

+ 'd, config: Config, ) -> Self { - unborrow!(a, b); - Self::new_inner(qdec, irq, a.degrade(), b.degrade(), None, config) + into_ref!(a, b); + Self::new_inner(qdec, irq, a.map_into(), b.map_into(), None, config) } pub fn new_with_led( - qdec: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - a: impl Unborrow + 'd, - b: impl Unborrow + 'd, - led: impl Unborrow + 'd, + qdec: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + a: impl Peripheral

+ 'd, + b: impl Peripheral

+ 'd, + led: impl Peripheral

+ 'd, config: Config, ) -> Self { - unborrow!(a, b, led); - Self::new_inner(qdec, irq, a.degrade(), b.degrade(), Some(led.degrade()), config) + into_ref!(a, b, led); + Self::new_inner(qdec, irq, a.map_into(), b.map_into(), Some(led.map_into()), config) } fn new_inner( - _t: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - a: AnyPin, - b: AnyPin, - led: Option, + p: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + a: PeripheralRef<'d, AnyPin>, + b: PeripheralRef<'d, AnyPin>, + led: Option>, config: Config, ) -> Self { - unborrow!(irq); + into_ref!(p, irq); let r = Self::regs(); // Select pins. @@ -131,7 +130,7 @@ impl<'d> Qdec<'d> { }); irq.enable(); - Self { phantom: PhantomData } + Self { _p: p } } /// Perform an asynchronous read of the decoder. diff --git a/embassy-nrf/src/qspi.rs b/embassy-nrf/src/qspi.rs index 92fa79b8a..67634b5b7 100644 --- a/embassy-nrf/src/qspi.rs +++ b/embassy-nrf/src/qspi.rs @@ -1,20 +1,18 @@ #![macro_use] -use core::marker::PhantomData; use core::ptr; use core::task::Poll; use embassy_hal_common::drop::DropBomb; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use futures::future::poll_fn; -use crate::gpio::sealed::Pin as _; use crate::gpio::{self, Pin as GpioPin}; use crate::interrupt::{Interrupt, InterruptExt}; pub use crate::pac::qspi::ifconfig0::{ ADDRMODE_A as AddressMode, PPSIZE_A as WritePageSize, READOC_A as ReadOpcode, WRITEOC_A as WriteOpcode, }; -use crate::{pac, Unborrow}; +use crate::{pac, Peripheral}; // TODO // - config: @@ -63,38 +61,38 @@ pub enum Error { } pub struct Qspi<'d, T: Instance, const FLASH_SIZE: usize> { - irq: T::Interrupt, + irq: PeripheralRef<'d, T::Interrupt>, dpm_enabled: bool, - phantom: PhantomData<&'d mut T>, } impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> { pub fn new( - _qspi: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - sck: impl Unborrow + 'd, - csn: impl Unborrow + 'd, - io0: impl Unborrow + 'd, - io1: impl Unborrow + 'd, - io2: impl Unborrow + 'd, - io3: impl Unborrow + 'd, + _qspi: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + sck: impl Peripheral

+ 'd, + csn: impl Peripheral

+ 'd, + io0: impl Peripheral

+ 'd, + io1: impl Peripheral

+ 'd, + io2: impl Peripheral

+ 'd, + io3: impl Peripheral

+ 'd, config: Config, ) -> Qspi<'d, T, FLASH_SIZE> { - unborrow!(irq, sck, csn, io0, io1, io2, io3); + into_ref!(irq, sck, csn, io0, io1, io2, io3); let r = T::regs(); - let sck = sck.degrade(); - let csn = csn.degrade(); - let io0 = io0.degrade(); - let io1 = io1.degrade(); - let io2 = io2.degrade(); - let io3 = io3.degrade(); - - for pin in [&sck, &csn, &io0, &io1, &io2, &io3] { - pin.set_high(); - pin.conf().write(|w| w.dir().output().drive().h0h1()); - } + sck.set_high(); + csn.set_high(); + io0.set_high(); + io1.set_high(); + io2.set_high(); + io3.set_high(); + sck.conf().write(|w| w.dir().output().drive().h0h1()); + csn.conf().write(|w| w.dir().output().drive().h0h1()); + io0.conf().write(|w| w.dir().output().drive().h0h1()); + io1.conf().write(|w| w.dir().output().drive().h0h1()); + io2.conf().write(|w| w.dir().output().drive().h0h1()); + io3.conf().write(|w| w.dir().output().drive().h0h1()); r.psel.sck.write(|w| unsafe { w.bits(sck.psel_bits()) }); r.psel.csn.write(|w| unsafe { w.bits(csn.psel_bits()) }); @@ -143,7 +141,6 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> { let mut res = Self { dpm_enabled: config.deep_power_down.is_some(), irq, - phantom: PhantomData, }; r.events_ready.reset(); @@ -536,7 +533,7 @@ pub(crate) mod sealed { } } -pub trait Instance: Unborrow + sealed::Instance + 'static { +pub trait Instance: Peripheral

+ sealed::Instance + 'static { type Interrupt: Interrupt; } diff --git a/embassy-nrf/src/rng.rs b/embassy-nrf/src/rng.rs index e68ed912e..9bebd6fa3 100644 --- a/embassy-nrf/src/rng.rs +++ b/embassy-nrf/src/rng.rs @@ -1,16 +1,15 @@ -use core::marker::PhantomData; use core::ptr; use core::sync::atomic::{AtomicPtr, Ordering}; use core::task::Poll; use embassy::waitqueue::AtomicWaker; use embassy_hal_common::drop::OnDrop; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use futures::future::poll_fn; use crate::interrupt::InterruptExt; use crate::peripherals::RNG; -use crate::{interrupt, pac, Unborrow}; +use crate::{interrupt, pac, Peripheral}; impl RNG { fn regs() -> &'static pac::rng::RegisterBlock { @@ -34,8 +33,7 @@ struct State { /// /// It has a non-blocking API, and a blocking api through `rand`. pub struct Rng<'d> { - irq: interrupt::RNG, - phantom: PhantomData<(&'d mut RNG, &'d mut interrupt::RNG)>, + irq: PeripheralRef<'d, interrupt::RNG>, } impl<'d> Rng<'d> { @@ -45,13 +43,10 @@ impl<'d> Rng<'d> { /// e.g. using `mem::forget`. /// /// The synchronous API is safe. - pub fn new(_rng: impl Unborrow + 'd, irq: impl Unborrow + 'd) -> Self { - unborrow!(irq); + pub fn new(_rng: impl Peripheral

+ 'd, irq: impl Peripheral

+ 'd) -> Self { + into_ref!(irq); - let this = Self { - irq, - phantom: PhantomData, - }; + let this = Self { irq }; this.stop(); this.disable_irq(); diff --git a/embassy-nrf/src/saadc.rs b/embassy-nrf/src/saadc.rs index af1aa8812..6ddc70e52 100644 --- a/embassy-nrf/src/saadc.rs +++ b/embassy-nrf/src/saadc.rs @@ -1,11 +1,10 @@ #![macro_use] -use core::marker::PhantomData; use core::sync::atomic::{compiler_fence, Ordering}; use core::task::Poll; use embassy::waitqueue::AtomicWaker; -use embassy_hal_common::unborrow; +use embassy_hal_common::{impl_peripheral, into_ref, PeripheralRef}; use futures::future::poll_fn; use pac::{saadc, SAADC}; use saadc::ch::config::{GAIN_A, REFSEL_A, RESP_A, TACQ_A}; @@ -14,10 +13,11 @@ pub(crate) use saadc::ch::pselp::PSELP_A as InputChannel; use saadc::oversample::OVERSAMPLE_A; use saadc::resolution::VAL_A; +use self::sealed::Input as _; use crate::interrupt::InterruptExt; use crate::ppi::{ConfigurableChannel, Event, Ppi, Task}; use crate::timer::{Frequency, Instance as TimerInstance, Timer}; -use crate::{interrupt, pac, peripherals, Unborrow}; +use crate::{interrupt, pac, peripherals, Peripheral}; #[derive(Debug, Clone, Copy, PartialEq, Eq)] #[cfg_attr(feature = "defmt", derive(defmt::Format))] @@ -26,7 +26,7 @@ pub enum Error {} /// One-shot and continuous SAADC. pub struct Saadc<'d, const N: usize> { - phantom: PhantomData<&'d mut peripherals::SAADC>, + _p: PeripheralRef<'d, peripherals::SAADC>, } static WAKER: AtomicWaker = AtomicWaker::new(); @@ -66,106 +66,37 @@ pub struct ChannelConfig<'d> { /// Acquisition time in microseconds. pub time: Time, /// Positive channel to sample - p_channel: InputChannel, + p_channel: PeripheralRef<'d, AnyInput>, /// An optional negative channel to sample - n_channel: Option, - - phantom: PhantomData<&'d ()>, + n_channel: Option>, } -/// A dummy `Input` pin implementation for SAADC peripheral sampling from the -/// internal voltage. -pub struct VddInput; - -unsafe impl Unborrow for VddInput { - type Target = VddInput; - unsafe fn unborrow(self) -> Self::Target { - self - } -} - -impl sealed::Input for VddInput { - #[cfg(not(feature = "_nrf9160"))] - fn channel(&self) -> InputChannel { - InputChannel::VDD - } - #[cfg(feature = "_nrf9160")] - fn channel(&self) -> InputChannel { - InputChannel::VDDGPIO - } -} -impl Input for VddInput {} - -/// A dummy `Input` pin implementation for SAADC peripheral sampling from the -/// VDDH / 5 voltage. -#[cfg(any(feature = "_nrf5340-app", feature = "nrf52833", feature = "nrf52840"))] -pub struct VddhDiv5Input; - -#[cfg(any(feature = "_nrf5340-app", feature = "nrf52833", feature = "nrf52840"))] -unsafe impl Unborrow for VddhDiv5Input { - type Target = VddhDiv5Input; - unsafe fn unborrow(self) -> Self::Target { - self - } -} - -#[cfg(any(feature = "_nrf5340-app", feature = "nrf52833", feature = "nrf52840"))] -impl sealed::Input for VddhDiv5Input { - fn channel(&self) -> InputChannel { - InputChannel::VDDHDIV5 - } -} - -#[cfg(any(feature = "_nrf5340-app", feature = "nrf52833", feature = "nrf52840"))] -impl Input for VddhDiv5Input {} - -pub struct AnyInput { - channel: InputChannel, -} - -unsafe impl Unborrow for AnyInput { - type Target = AnyInput; - unsafe fn unborrow(self) -> Self::Target { - self - } -} - -impl sealed::Input for AnyInput { - fn channel(&self) -> InputChannel { - self.channel - } -} - -impl Input for AnyInput {} - impl<'d> ChannelConfig<'d> { /// Default configuration for single ended channel sampling. - pub fn single_ended(input: impl Unborrow + 'd) -> Self { - unborrow!(input); + pub fn single_ended(input: impl Peripheral

+ 'd) -> Self { + into_ref!(input); Self { reference: Reference::INTERNAL, gain: Gain::GAIN1_6, resistor: Resistor::BYPASS, time: Time::_10US, - p_channel: input.channel(), + p_channel: input.map_into(), n_channel: None, - phantom: PhantomData, } } /// Default configuration for differential channel sampling. pub fn differential( - p_input: impl Unborrow + 'd, - n_input: impl Unborrow + 'd, + p_input: impl Peripheral

+ 'd, + n_input: impl Peripheral

+ 'd, ) -> Self { - unborrow!(p_input, n_input); + into_ref!(p_input, n_input); Self { reference: Reference::INTERNAL, gain: Gain::GAIN1_6, resistor: Resistor::BYPASS, time: Time::_10US, - p_channel: p_input.channel(), - n_channel: Some(n_input.channel()), - phantom: PhantomData, + p_channel: p_input.map_into(), + n_channel: Some(n_input.map_into()), } } } @@ -182,12 +113,12 @@ pub enum SamplerState { impl<'d, const N: usize> Saadc<'d, N> { pub fn new( - _saadc: impl Unborrow + 'd, - irq: impl Unborrow + 'd, + saadc: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, config: Config, channel_configs: [ChannelConfig; N], ) -> Self { - unborrow!(irq); + into_ref!(saadc, irq); let r = unsafe { &*SAADC::ptr() }; @@ -199,9 +130,11 @@ impl<'d, const N: usize> Saadc<'d, N> { r.oversample.write(|w| w.oversample().variant(oversample.into())); for (i, cc) in channel_configs.iter().enumerate() { - r.ch[i].pselp.write(|w| w.pselp().variant(cc.p_channel)); - if let Some(n_channel) = cc.n_channel { - r.ch[i].pseln.write(|w| unsafe { w.pseln().bits(n_channel as u8) }); + r.ch[i].pselp.write(|w| w.pselp().variant(cc.p_channel.channel())); + if let Some(n_channel) = &cc.n_channel { + r.ch[i] + .pseln + .write(|w| unsafe { w.pseln().bits(n_channel.channel() as u8) }); } r.ch[i].config.write(|w| { w.refsel().variant(cc.reference.into()); @@ -230,7 +163,7 @@ impl<'d, const N: usize> Saadc<'d, N> { irq.unpend(); irq.enable(); - Self { phantom: PhantomData } + Self { _p: saadc } } fn on_interrupt(_ctx: *mut ()) { @@ -689,7 +622,7 @@ pub(crate) mod sealed { } /// An input that can be used as either or negative end of a ADC differential in the SAADC periperhal. -pub trait Input: sealed::Input + Unborrow + Sized { +pub trait Input: sealed::Input + Into + Peripheral

+ Sized + 'static { fn degrade_saadc(self) -> AnyInput { AnyInput { channel: self.channel(), @@ -697,13 +630,57 @@ pub trait Input: sealed::Input + Unborrow + Sized { } } +pub struct AnyInput { + channel: InputChannel, +} + +impl_peripheral!(AnyInput); + +impl sealed::Input for AnyInput { + fn channel(&self) -> InputChannel { + self.channel + } +} + +impl Input for AnyInput {} + macro_rules! impl_saadc_input { ($pin:ident, $ch:ident) => { - impl crate::saadc::sealed::Input for crate::peripherals::$pin { + impl_saadc_input!(@local, crate::peripherals::$pin, $ch); + }; + (@local, $pin:ty, $ch:ident) => { + impl crate::saadc::sealed::Input for $pin { fn channel(&self) -> crate::saadc::InputChannel { crate::saadc::InputChannel::$ch } } - impl crate::saadc::Input for crate::peripherals::$pin {} + impl crate::saadc::Input for $pin {} + + impl From<$pin> for crate::saadc::AnyInput { + fn from(val: $pin) -> Self { + crate::saadc::Input::degrade_saadc(val) + } + } }; } + +/// A dummy `Input` pin implementation for SAADC peripheral sampling from the +/// internal voltage. +pub struct VddInput; + +impl_peripheral!(VddInput); +#[cfg(not(feature = "_nrf9160"))] +impl_saadc_input!(@local, VddInput, VDD); +#[cfg(feature = "_nrf9160")] +impl_saadc_input!(@local, VddInput, VDDGPIO); + +/// A dummy `Input` pin implementation for SAADC peripheral sampling from the +/// VDDH / 5 voltage. +#[cfg(any(feature = "_nrf5340-app", feature = "nrf52833", feature = "nrf52840"))] +pub struct VddhDiv5Input; + +#[cfg(any(feature = "_nrf5340-app", feature = "nrf52833", feature = "nrf52840"))] +impl_peripheral!(VddhDiv5Input); + +#[cfg(any(feature = "_nrf5340-app", feature = "nrf52833", feature = "nrf52840"))] +impl_saadc_input!(@local, VddhDiv5Input, VDDHDIV5); diff --git a/embassy-nrf/src/spim.rs b/embassy-nrf/src/spim.rs index d34d9a0c8..a512b4813 100644 --- a/embassy-nrf/src/spim.rs +++ b/embassy-nrf/src/spim.rs @@ -1,11 +1,10 @@ #![macro_use] -use core::marker::PhantomData; use core::sync::atomic::{compiler_fence, Ordering}; use core::task::Poll; use embassy_embedded_hal::SetConfig; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; pub use embedded_hal_02::spi::{Mode, Phase, Polarity, MODE_0, MODE_1, MODE_2, MODE_3}; use futures::future::poll_fn; pub use pac::spim0::frequency::FREQUENCY_A as Frequency; @@ -15,7 +14,7 @@ use crate::gpio::sealed::Pin as _; use crate::gpio::{self, AnyPin, Pin as GpioPin, PselBits}; use crate::interrupt::{Interrupt, InterruptExt}; use crate::util::{slice_in_ram_or, slice_ptr_parts, slice_ptr_parts_mut}; -use crate::{pac, Unborrow}; +use crate::{pac, Peripheral}; #[derive(Debug, Clone, Copy, PartialEq, Eq)] #[cfg_attr(feature = "defmt", derive(defmt::Format))] @@ -31,7 +30,7 @@ pub enum Error { /// /// For more details about EasyDMA, consult the module documentation. pub struct Spim<'d, T: Instance> { - phantom: PhantomData<&'d mut T>, + _p: PeripheralRef<'d, T>, } #[non_exhaustive] @@ -53,55 +52,55 @@ impl Default for Config { impl<'d, T: Instance> Spim<'d, T> { pub fn new( - spim: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - sck: impl Unborrow + 'd, - miso: impl Unborrow + 'd, - mosi: impl Unborrow + 'd, + spim: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + sck: impl Peripheral

+ 'd, + miso: impl Peripheral

+ 'd, + mosi: impl Peripheral

+ 'd, config: Config, ) -> Self { - unborrow!(sck, miso, mosi); + into_ref!(sck, miso, mosi); Self::new_inner( spim, irq, - sck.degrade(), - Some(miso.degrade()), - Some(mosi.degrade()), + sck.map_into(), + Some(miso.map_into()), + Some(mosi.map_into()), config, ) } pub fn new_txonly( - spim: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - sck: impl Unborrow + 'd, - mosi: impl Unborrow + 'd, + spim: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + sck: impl Peripheral

+ 'd, + mosi: impl Peripheral

+ 'd, config: Config, ) -> Self { - unborrow!(sck, mosi); - Self::new_inner(spim, irq, sck.degrade(), None, Some(mosi.degrade()), config) + into_ref!(sck, mosi); + Self::new_inner(spim, irq, sck.map_into(), None, Some(mosi.map_into()), config) } pub fn new_rxonly( - spim: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - sck: impl Unborrow + 'd, - miso: impl Unborrow + 'd, + spim: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + sck: impl Peripheral

+ 'd, + miso: impl Peripheral

+ 'd, config: Config, ) -> Self { - unborrow!(sck, miso); - Self::new_inner(spim, irq, sck.degrade(), Some(miso.degrade()), None, config) + into_ref!(sck, miso); + Self::new_inner(spim, irq, sck.map_into(), Some(miso.map_into()), None, config) } fn new_inner( - _spim: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - sck: AnyPin, - miso: Option, - mosi: Option, + spim: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + sck: PeripheralRef<'d, AnyPin>, + miso: Option>, + mosi: Option>, config: Config, ) -> Self { - unborrow!(irq); + into_ref!(spim, irq); let r = T::regs(); @@ -181,7 +180,7 @@ impl<'d, T: Instance> Spim<'d, T> { irq.unpend(); irq.enable(); - Self { phantom: PhantomData } + Self { _p: spim } } fn on_interrupt(_: *mut ()) { @@ -386,7 +385,7 @@ pub(crate) mod sealed { } } -pub trait Instance: Unborrow + sealed::Instance + 'static { +pub trait Instance: Peripheral

+ sealed::Instance + 'static { type Interrupt: Interrupt; } diff --git a/embassy-nrf/src/temp.rs b/embassy-nrf/src/temp.rs index 43ba3e042..a3b25ce05 100644 --- a/embassy-nrf/src/temp.rs +++ b/embassy-nrf/src/temp.rs @@ -1,29 +1,27 @@ //! Temperature sensor interface. -use core::marker::PhantomData; use core::task::Poll; use embassy::waitqueue::AtomicWaker; use embassy_hal_common::drop::OnDrop; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use fixed::types::I30F2; use futures::future::poll_fn; use crate::interrupt::InterruptExt; use crate::peripherals::TEMP; -use crate::{interrupt, pac, Unborrow}; +use crate::{interrupt, pac, Peripheral}; /// Integrated temperature sensor. pub struct Temp<'d> { - _temp: PhantomData<&'d TEMP>, - _irq: interrupt::TEMP, + _irq: PeripheralRef<'d, interrupt::TEMP>, } static WAKER: AtomicWaker = AtomicWaker::new(); impl<'d> Temp<'d> { - pub fn new(_t: impl Unborrow + 'd, irq: impl Unborrow + 'd) -> Self { - unborrow!(_t, irq); + pub fn new(_t: impl Peripheral

+ 'd, irq: impl Peripheral

+ 'd) -> Self { + into_ref!(_t, irq); // Enable interrupt that signals temperature values irq.disable(); @@ -33,10 +31,7 @@ impl<'d> Temp<'d> { WAKER.wake(); }); irq.enable(); - Self { - _temp: PhantomData, - _irq: irq, - } + Self { _irq: irq } } /// Perform an asynchronous temperature measurement. The returned future diff --git a/embassy-nrf/src/timer.rs b/embassy-nrf/src/timer.rs index c8c36dfae..8deecdc03 100644 --- a/embassy-nrf/src/timer.rs +++ b/embassy-nrf/src/timer.rs @@ -5,12 +5,12 @@ use core::task::Poll; use embassy::waitqueue::AtomicWaker; use embassy_hal_common::drop::OnDrop; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use futures::future::poll_fn; use crate::interrupt::{Interrupt, InterruptExt}; use crate::ppi::{Event, Task}; -use crate::{pac, Unborrow}; +use crate::{pac, Peripheral}; pub(crate) mod sealed { @@ -28,7 +28,7 @@ pub(crate) mod sealed { pub trait TimerType {} } -pub trait Instance: Unborrow + sealed::Instance + 'static + Send { +pub trait Instance: Peripheral

+ sealed::Instance + 'static + Send { type Interrupt: Interrupt; } pub trait ExtendedInstance: Instance + sealed::ExtendedInstance {} @@ -95,15 +95,13 @@ impl TimerType for Awaitable {} impl TimerType for NotAwaitable {} pub struct Timer<'d, T: Instance, I: TimerType = NotAwaitable> { - phantom: PhantomData<(&'d mut T, I)>, + _p: PeripheralRef<'d, T>, + _i: PhantomData, } impl<'d, T: Instance> Timer<'d, T, Awaitable> { - pub fn new_awaitable( - timer: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - ) -> Self { - unborrow!(irq); + pub fn new_awaitable(timer: impl Peripheral

+ 'd, irq: impl Peripheral

+ 'd) -> Self { + into_ref!(irq); irq.set_handler(Self::on_interrupt); irq.unpend(); @@ -117,7 +115,7 @@ impl<'d, T: Instance> Timer<'d, T, NotAwaitable> { /// /// This can be useful for triggering tasks via PPI /// `Uarte` uses this internally. - pub fn new(timer: impl Unborrow + 'd) -> Self { + pub fn new(timer: impl Peripheral

+ 'd) -> Self { Self::new_irqless(timer) } } @@ -126,10 +124,15 @@ impl<'d, T: Instance, I: TimerType> Timer<'d, T, I> { /// Create a `Timer` without an interrupt, meaning `Cc::wait` won't work. /// /// This is used by the public constructors. - fn new_irqless(_timer: impl Unborrow + 'd) -> Self { + fn new_irqless(timer: impl Peripheral

+ 'd) -> Self { + into_ref!(timer); + let regs = T::regs(); - let mut this = Self { phantom: PhantomData }; + let mut this = Self { + _p: timer, + _i: PhantomData, + }; // Stop the timer before doing anything else, // since changing BITMODE while running can cause 'unpredictable behaviour' according to the specification. @@ -233,7 +236,8 @@ impl<'d, T: Instance, I: TimerType> Timer<'d, T, I> { } Cc { n, - phantom: PhantomData, + _p: self._p.reborrow(), + _i: PhantomData, } } } @@ -245,12 +249,13 @@ impl<'d, T: Instance, I: TimerType> Timer<'d, T, I> { /// /// The timer will fire the register's COMPARE event when its counter reaches the value stored in the register. /// When the register's CAPTURE task is triggered, the timer will store the current value of its counter in the register -pub struct Cc<'a, T: Instance, I: TimerType = NotAwaitable> { +pub struct Cc<'d, T: Instance, I: TimerType = NotAwaitable> { n: usize, - phantom: PhantomData<(&'a mut T, I)>, + _p: PeripheralRef<'d, T>, + _i: PhantomData, } -impl<'a, T: Instance> Cc<'a, T, Awaitable> { +impl<'d, T: Instance> Cc<'d, T, Awaitable> { /// Wait until the timer's counter reaches the value stored in this register. /// /// This requires a mutable reference so that this task's waker cannot be overwritten by a second call to `wait`. @@ -284,9 +289,9 @@ impl<'a, T: Instance> Cc<'a, T, Awaitable> { on_drop.defuse(); } } -impl<'a, T: Instance> Cc<'a, T, NotAwaitable> {} +impl<'d, T: Instance> Cc<'d, T, NotAwaitable> {} -impl<'a, T: Instance, I: TimerType> Cc<'a, T, I> { +impl<'d, T: Instance, I: TimerType> Cc<'d, T, I> { /// Get the current value stored in the register. pub fn read(&self) -> u32 { T::regs().cc[self.n].read().cc().bits() diff --git a/embassy-nrf/src/twim.rs b/embassy-nrf/src/twim.rs index 2088691b2..6d6eb84e7 100644 --- a/embassy-nrf/src/twim.rs +++ b/embassy-nrf/src/twim.rs @@ -7,7 +7,6 @@ //! - nRF52832: Section 33 //! - nRF52840: Section 6.31 use core::future::Future; -use core::marker::PhantomData; use core::sync::atomic::compiler_fence; use core::sync::atomic::Ordering::SeqCst; use core::task::Poll; @@ -16,14 +15,14 @@ use core::task::Poll; use embassy::time::{Duration, Instant}; use embassy::waitqueue::AtomicWaker; use embassy_embedded_hal::SetConfig; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use futures::future::poll_fn; use crate::chip::{EASY_DMA_SIZE, FORCE_COPY_BUFFER_SIZE}; use crate::gpio::Pin as GpioPin; use crate::interrupt::{Interrupt, InterruptExt}; use crate::util::{slice_in_ram, slice_in_ram_or}; -use crate::{gpio, pac, Unborrow}; +use crate::{gpio, pac, Peripheral}; #[derive(Clone, Copy)] pub enum Frequency { @@ -75,18 +74,18 @@ pub enum Error { /// /// For more details about EasyDMA, consult the module documentation. pub struct Twim<'d, T: Instance> { - phantom: PhantomData<&'d mut T>, + _p: PeripheralRef<'d, T>, } impl<'d, T: Instance> Twim<'d, T> { pub fn new( - _twim: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - sda: impl Unborrow + 'd, - scl: impl Unborrow + 'd, + twim: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + sda: impl Peripheral

+ 'd, + scl: impl Peripheral

+ 'd, config: Config, ) -> Self { - unborrow!(irq, sda, scl); + into_ref!(twim, irq, sda, scl); let r = T::regs(); @@ -136,7 +135,7 @@ impl<'d, T: Instance> Twim<'d, T> { irq.unpend(); irq.enable(); - Self { phantom: PhantomData } + Self { _p: twim } } fn on_interrupt(_: *mut ()) { @@ -707,7 +706,7 @@ pub(crate) mod sealed { } } -pub trait Instance: Unborrow + sealed::Instance + 'static { +pub trait Instance: Peripheral

+ sealed::Instance + 'static { type Interrupt: Interrupt; } diff --git a/embassy-nrf/src/uarte.rs b/embassy-nrf/src/uarte.rs index 459c56c8e..792b8ecca 100644 --- a/embassy-nrf/src/uarte.rs +++ b/embassy-nrf/src/uarte.rs @@ -13,12 +13,11 @@ //! memory may be used given that buffers are passed in directly to its read and write //! methods. -use core::marker::PhantomData; use core::sync::atomic::{compiler_fence, Ordering}; use core::task::Poll; use embassy_hal_common::drop::OnDrop; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use futures::future::poll_fn; use pac::uarte0::RegisterBlock; // Re-export SVD variants to allow user to directly set values. @@ -31,7 +30,7 @@ use crate::interrupt::{Interrupt, InterruptExt}; use crate::ppi::{AnyConfigurableChannel, ConfigurableChannel, Event, Ppi, Task}; use crate::timer::{Frequency, Instance as TimerInstance, Timer}; use crate::util::slice_in_ram_or; -use crate::{pac, Unborrow}; +use crate::{pac, Peripheral}; #[derive(Clone)] #[non_exhaustive] @@ -63,7 +62,6 @@ pub enum Error { /// /// For more details about EasyDMA, consult the module documentation. pub struct Uarte<'d, T: Instance> { - phantom: PhantomData<&'d mut T>, tx: UarteTx<'d, T>, rx: UarteRx<'d, T>, } @@ -71,60 +69,60 @@ pub struct Uarte<'d, T: Instance> { /// Transmitter interface to the UARTE peripheral obtained /// via [Uarte]::split. pub struct UarteTx<'d, T: Instance> { - phantom: PhantomData<&'d mut T>, + _p: PeripheralRef<'d, T>, } /// Receiver interface to the UARTE peripheral obtained /// via [Uarte]::split. pub struct UarteRx<'d, T: Instance> { - phantom: PhantomData<&'d mut T>, + _p: PeripheralRef<'d, T>, } impl<'d, T: Instance> Uarte<'d, T> { /// Create a new UARTE without hardware flow control pub fn new( - uarte: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - rxd: impl Unborrow + 'd, - txd: impl Unborrow + 'd, + uarte: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + rxd: impl Peripheral

+ 'd, + txd: impl Peripheral

+ 'd, config: Config, ) -> Self { - unborrow!(rxd, txd); - Self::new_inner(uarte, irq, rxd.degrade(), txd.degrade(), None, None, config) + into_ref!(rxd, txd); + Self::new_inner(uarte, irq, rxd.map_into(), txd.map_into(), None, None, config) } /// Create a new UARTE with hardware flow control (RTS/CTS) pub fn new_with_rtscts( - uarte: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - rxd: impl Unborrow + 'd, - txd: impl Unborrow + 'd, - cts: impl Unborrow + 'd, - rts: impl Unborrow + 'd, + uarte: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + rxd: impl Peripheral

+ 'd, + txd: impl Peripheral

+ 'd, + cts: impl Peripheral

+ 'd, + rts: impl Peripheral

+ 'd, config: Config, ) -> Self { - unborrow!(rxd, txd, cts, rts); + into_ref!(rxd, txd, cts, rts); Self::new_inner( uarte, irq, - rxd.degrade(), - txd.degrade(), - Some(cts.degrade()), - Some(rts.degrade()), + rxd.map_into(), + txd.map_into(), + Some(cts.map_into()), + Some(rts.map_into()), config, ) } fn new_inner( - _uarte: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - rxd: AnyPin, - txd: AnyPin, - cts: Option, - rts: Option, + uarte: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + rxd: PeripheralRef<'d, AnyPin>, + txd: PeripheralRef<'d, AnyPin>, + cts: Option>, + rts: Option>, config: Config, ) -> Self { - unborrow!(irq); + into_ref!(uarte, irq); let r = T::regs(); @@ -161,9 +159,10 @@ impl<'d, T: Instance> Uarte<'d, T> { s.tx_rx_refcount.store(2, Ordering::Relaxed); Self { - phantom: PhantomData, - tx: UarteTx { phantom: PhantomData }, - rx: UarteRx { phantom: PhantomData }, + tx: UarteTx { + _p: unsafe { uarte.clone_unchecked() }, + }, + rx: UarteRx { _p: uarte }, } } @@ -245,35 +244,35 @@ fn configure(r: &RegisterBlock, config: Config, hardware_flow_control: bool) { impl<'d, T: Instance> UarteTx<'d, T> { /// Create a new tx-only UARTE without hardware flow control pub fn new( - uarte: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - txd: impl Unborrow + 'd, + uarte: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + txd: impl Peripheral

+ 'd, config: Config, ) -> Self { - unborrow!(txd); - Self::new_inner(uarte, irq, txd.degrade(), None, config) + into_ref!(txd); + Self::new_inner(uarte, irq, txd.map_into(), None, config) } /// Create a new tx-only UARTE with hardware flow control (RTS/CTS) pub fn new_with_rtscts( - uarte: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - txd: impl Unborrow + 'd, - cts: impl Unborrow + 'd, + uarte: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + txd: impl Peripheral

+ 'd, + cts: impl Peripheral

+ 'd, config: Config, ) -> Self { - unborrow!(txd, cts); - Self::new_inner(uarte, irq, txd.degrade(), Some(cts.degrade()), config) + into_ref!(txd, cts); + Self::new_inner(uarte, irq, txd.map_into(), Some(cts.map_into()), config) } fn new_inner( - _uarte: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - txd: AnyPin, - cts: Option, + uarte: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + txd: PeripheralRef<'d, AnyPin>, + cts: Option>, config: Config, ) -> Self { - unborrow!(irq); + into_ref!(uarte, irq); let r = T::regs(); @@ -299,7 +298,7 @@ impl<'d, T: Instance> UarteTx<'d, T> { let s = T::state(); s.tx_rx_refcount.store(1, Ordering::Relaxed); - Self { phantom: PhantomData } + Self { _p: uarte } } pub async fn write(&mut self, buffer: &[u8]) -> Result<(), Error> { @@ -437,35 +436,35 @@ impl<'a, T: Instance> Drop for UarteTx<'a, T> { impl<'d, T: Instance> UarteRx<'d, T> { /// Create a new rx-only UARTE without hardware flow control pub fn new( - uarte: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - rxd: impl Unborrow + 'd, + uarte: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + rxd: impl Peripheral

+ 'd, config: Config, ) -> Self { - unborrow!(rxd); - Self::new_inner(uarte, irq, rxd.degrade(), None, config) + into_ref!(rxd); + Self::new_inner(uarte, irq, rxd.map_into(), None, config) } /// Create a new rx-only UARTE with hardware flow control (RTS/CTS) pub fn new_with_rtscts( - uarte: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - rxd: impl Unborrow + 'd, - rts: impl Unborrow + 'd, + uarte: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + rxd: impl Peripheral

+ 'd, + rts: impl Peripheral

+ 'd, config: Config, ) -> Self { - unborrow!(rxd, rts); - Self::new_inner(uarte, irq, rxd.degrade(), Some(rts.degrade()), config) + into_ref!(rxd, rts); + Self::new_inner(uarte, irq, rxd.map_into(), Some(rts.map_into()), config) } fn new_inner( - _uarte: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - rxd: AnyPin, - rts: Option, + uarte: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + rxd: PeripheralRef<'d, AnyPin>, + rts: Option>, config: Config, ) -> Self { - unborrow!(irq); + into_ref!(uarte, irq); let r = T::regs(); @@ -491,7 +490,7 @@ impl<'d, T: Instance> UarteRx<'d, T> { let s = T::state(); s.tx_rx_refcount.store(1, Ordering::Relaxed); - Self { phantom: PhantomData } + Self { _p: uarte } } pub async fn read(&mut self, buffer: &mut [u8]) -> Result<(), Error> { @@ -676,24 +675,24 @@ pub struct UarteWithIdle<'d, U: Instance, T: TimerInstance> { impl<'d, U: Instance, T: TimerInstance> UarteWithIdle<'d, U, T> { /// Create a new UARTE without hardware flow control pub fn new( - uarte: impl Unborrow + 'd, - timer: impl Unborrow + 'd, - ppi_ch1: impl Unborrow + 'd, - ppi_ch2: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - rxd: impl Unborrow + 'd, - txd: impl Unborrow + 'd, + uarte: impl Peripheral

+ 'd, + timer: impl Peripheral

+ 'd, + ppi_ch1: impl Peripheral

+ 'd, + ppi_ch2: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + rxd: impl Peripheral

+ 'd, + txd: impl Peripheral

+ 'd, config: Config, ) -> Self { - unborrow!(rxd, txd); + into_ref!(rxd, txd); Self::new_inner( uarte, timer, ppi_ch1, ppi_ch2, irq, - rxd.degrade(), - txd.degrade(), + rxd.map_into(), + txd.map_into(), None, None, config, @@ -702,42 +701,42 @@ impl<'d, U: Instance, T: TimerInstance> UarteWithIdle<'d, U, T> { /// Create a new UARTE with hardware flow control (RTS/CTS) pub fn new_with_rtscts( - uarte: impl Unborrow + 'd, - timer: impl Unborrow + 'd, - ppi_ch1: impl Unborrow + 'd, - ppi_ch2: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - rxd: impl Unborrow + 'd, - txd: impl Unborrow + 'd, - cts: impl Unborrow + 'd, - rts: impl Unborrow + 'd, + uarte: impl Peripheral

+ 'd, + timer: impl Peripheral

+ 'd, + ppi_ch1: impl Peripheral

+ 'd, + ppi_ch2: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + rxd: impl Peripheral

+ 'd, + txd: impl Peripheral

+ 'd, + cts: impl Peripheral

+ 'd, + rts: impl Peripheral

+ 'd, config: Config, ) -> Self { - unborrow!(rxd, txd, cts, rts); + into_ref!(rxd, txd, cts, rts); Self::new_inner( uarte, timer, ppi_ch1, ppi_ch2, irq, - rxd.degrade(), - txd.degrade(), - Some(cts.degrade()), - Some(rts.degrade()), + rxd.map_into(), + txd.map_into(), + Some(cts.map_into()), + Some(rts.map_into()), config, ) } fn new_inner( - uarte: impl Unborrow + 'd, - timer: impl Unborrow + 'd, - ppi_ch1: impl Unborrow + 'd, - ppi_ch2: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - rxd: AnyPin, - txd: AnyPin, - cts: Option, - rts: Option, + uarte: impl Peripheral

+ 'd, + timer: impl Peripheral

+ 'd, + ppi_ch1: impl Peripheral

+ 'd, + ppi_ch2: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + rxd: PeripheralRef<'d, AnyPin>, + txd: PeripheralRef<'d, AnyPin>, + cts: Option>, + rts: Option>, config: Config, ) -> Self { let baudrate = config.baudrate; @@ -745,7 +744,7 @@ impl<'d, U: Instance, T: TimerInstance> UarteWithIdle<'d, U, T> { let mut timer = Timer::new(timer); - unborrow!(ppi_ch1, ppi_ch2); + into_ref!(ppi_ch1, ppi_ch2); let r = U::regs(); @@ -763,7 +762,7 @@ impl<'d, U: Instance, T: TimerInstance> UarteWithIdle<'d, U, T> { timer.cc(0).short_compare_stop(); let mut ppi_ch1 = Ppi::new_one_to_two( - ppi_ch1.degrade(), + ppi_ch1.map_into(), Event::from_reg(&r.events_rxdrdy), timer.task_clear(), timer.task_start(), @@ -771,7 +770,7 @@ impl<'d, U: Instance, T: TimerInstance> UarteWithIdle<'d, U, T> { ppi_ch1.enable(); let mut ppi_ch2 = Ppi::new_one_to_one( - ppi_ch2.degrade(), + ppi_ch2.map_into(), timer.cc(0).event_compare(), Task::from_reg(&r.tasks_stoprx), ); @@ -958,7 +957,7 @@ pub(crate) mod sealed { } } -pub trait Instance: Unborrow + sealed::Instance + 'static + Send { +pub trait Instance: Peripheral

+ sealed::Instance + 'static + Send { type Interrupt: Interrupt; } diff --git a/embassy-nrf/src/usb.rs b/embassy-nrf/src/usb.rs index a039427f1..378492859 100644 --- a/embassy-nrf/src/usb.rs +++ b/embassy-nrf/src/usb.rs @@ -7,7 +7,7 @@ use core::task::Poll; use cortex_m::peripheral::NVIC; use embassy::waitqueue::AtomicWaker; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; pub use embassy_usb; use embassy_usb::driver::{self, EndpointError, Event, Unsupported}; use embassy_usb::types::{EndpointAddress, EndpointInfo, EndpointType, UsbDirection}; @@ -17,7 +17,7 @@ use pac::usbd::RegisterBlock; use crate::interrupt::{Interrupt, InterruptExt}; use crate::util::slice_in_ram; -use crate::{pac, Unborrow}; +use crate::{pac, Peripheral}; const NEW_AW: AtomicWaker = AtomicWaker::new(); static BUS_WAKER: AtomicWaker = NEW_AW; @@ -38,7 +38,7 @@ pub trait UsbSupply { } pub struct Driver<'d, T: Instance, P: UsbSupply> { - phantom: PhantomData<&'d mut T>, + _p: PeripheralRef<'d, T>, alloc_in: Allocator, alloc_out: Allocator, usb_supply: P, @@ -166,18 +166,14 @@ impl UsbSupply for SignalledSupply { } impl<'d, T: Instance, P: UsbSupply> Driver<'d, T, P> { - pub fn new( - _usb: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - usb_supply: P, - ) -> Self { - unborrow!(irq); + pub fn new(usb: impl Peripheral

+ 'd, irq: impl Peripheral

+ 'd, usb_supply: P) -> Self { + into_ref!(usb, irq); irq.set_handler(Self::on_interrupt); irq.unpend(); irq.enable(); Self { - phantom: PhantomData, + _p: usb, alloc_in: Allocator::new(), alloc_out: Allocator::new(), usb_supply, @@ -273,15 +269,15 @@ impl<'d, T: Instance, P: UsbSupply + 'd> driver::Driver<'d> for Driver<'d, T, P> })) } - fn start(self, control_max_packet_size: u16) -> (Self::Bus, Self::ControlPipe) { + fn start(mut self, control_max_packet_size: u16) -> (Self::Bus, Self::ControlPipe) { ( Bus { - phantom: PhantomData, + _p: unsafe { self._p.clone_unchecked() }, power_available: false, usb_supply: self.usb_supply, }, ControlPipe { - _phantom: PhantomData, + _p: self._p, max_packet_size: control_max_packet_size, }, ) @@ -289,7 +285,7 @@ impl<'d, T: Instance, P: UsbSupply + 'd> driver::Driver<'d> for Driver<'d, T, P> } pub struct Bus<'d, T: Instance, P: UsbSupply> { - phantom: PhantomData<&'d mut T>, + _p: PeripheralRef<'d, T>, power_available: bool, usb_supply: P, } @@ -750,7 +746,7 @@ impl<'d, T: Instance> driver::EndpointIn for Endpoint<'d, T, In> { } pub struct ControlPipe<'d, T: Instance> { - _phantom: PhantomData<&'d mut T>, + _p: PeripheralRef<'d, T>, max_packet_size: u16, } @@ -950,7 +946,7 @@ pub(crate) mod sealed { } } -pub trait Instance: Unborrow + sealed::Instance + 'static + Send { +pub trait Instance: Peripheral

+ sealed::Instance + 'static + Send { type Interrupt: Interrupt; } diff --git a/embassy-rp/src/gpio.rs b/embassy-rp/src/gpio.rs index 53c26de1c..5db1a690b 100644 --- a/embassy-rp/src/gpio.rs +++ b/embassy-rp/src/gpio.rs @@ -1,15 +1,15 @@ +#![macro_use] use core::future::Future; -use core::marker::PhantomData; use core::pin::Pin as FuturePin; use core::task::{Context, Poll}; use embassy::waitqueue::AtomicWaker; use embassy_cortex_m::interrupt::{Interrupt, InterruptExt}; -use embassy_hal_common::{unborrow, unsafe_impl_unborrow}; +use embassy_hal_common::{impl_peripheral, into_ref, PeripheralRef}; use crate::pac::common::{Reg, RW}; use crate::pac::SIO; -use crate::{interrupt, pac, peripherals, Unborrow}; +use crate::{interrupt, pac, peripherals, Peripheral}; const PIN_COUNT: usize = 30; const NEW_AW: AtomicWaker = AtomicWaker::new(); @@ -61,7 +61,7 @@ pub struct Input<'d, T: Pin> { impl<'d, T: Pin> Input<'d, T> { #[inline] - pub fn new(pin: impl Unborrow + 'd, pull: Pull) -> Self { + pub fn new(pin: impl Peripheral

+ 'd, pull: Pull) -> Self { let mut pin = Flex::new(pin); pin.set_as_input(); pin.set_pull(pull); @@ -177,13 +177,13 @@ unsafe fn IO_IRQ_BANK0() { } struct InputFuture<'a, T: Pin> { - pin: &'a mut T, + pin: PeripheralRef<'a, T>, level: InterruptTrigger, - phantom: PhantomData<&'a mut AnyPin>, } impl<'d, T: Pin> InputFuture<'d, T> { - pub fn new(pin: &'d mut T, level: InterruptTrigger) -> Self { + pub fn new(pin: impl Peripheral

+ 'd, level: InterruptTrigger) -> Self { + into_ref!(pin); unsafe { let irq = interrupt::IO_IRQ_BANK0::steal(); irq.disable(); @@ -215,11 +215,7 @@ impl<'d, T: Pin> InputFuture<'d, T> { irq.enable(); } - Self { - pin, - level, - phantom: PhantomData, - } + Self { pin, level } } } @@ -294,7 +290,7 @@ pub struct Output<'d, T: Pin> { impl<'d, T: Pin> Output<'d, T> { #[inline] - pub fn new(pin: impl Unborrow + 'd, initial_output: Level) -> Self { + pub fn new(pin: impl Peripheral

+ 'd, initial_output: Level) -> Self { let mut pin = Flex::new(pin); match initial_output { Level::High => pin.set_high(), @@ -355,7 +351,7 @@ pub struct OutputOpenDrain<'d, T: Pin> { impl<'d, T: Pin> OutputOpenDrain<'d, T> { #[inline] - pub fn new(pin: impl Unborrow + 'd, initial_output: Level) -> Self { + pub fn new(pin: impl Peripheral

+ 'd, initial_output: Level) -> Self { let mut pin = Flex::new(pin); pin.set_low(); match initial_output { @@ -419,14 +415,13 @@ impl<'d, T: Pin> OutputOpenDrain<'d, T> { /// set while not in output mode, so the pin's level will be 'remembered' when it is not in output /// mode. pub struct Flex<'d, T: Pin> { - pin: T, - phantom: PhantomData<&'d mut T>, + pin: PeripheralRef<'d, T>, } impl<'d, T: Pin> Flex<'d, T> { #[inline] - pub fn new(pin: impl Unborrow + 'd) -> Self { - unborrow!(pin); + pub fn new(pin: impl Peripheral

+ 'd) -> Self { + into_ref!(pin); unsafe { pin.pad_ctrl().write(|w| { @@ -438,10 +433,7 @@ impl<'d, T: Pin> Flex<'d, T> { }); } - Self { - pin, - phantom: PhantomData, - } + Self { pin } } #[inline] @@ -655,7 +647,7 @@ pub(crate) mod sealed { } } -pub trait Pin: Unborrow + sealed::Pin { +pub trait Pin: Peripheral

+ Into + sealed::Pin + Sized + 'static { /// Degrade to a generic pin struct fn degrade(self) -> AnyPin { AnyPin { @@ -667,7 +659,9 @@ pub trait Pin: Unborrow + sealed::Pin { pub struct AnyPin { pin_bank: u8, } -unsafe_impl_unborrow!(AnyPin); + +impl_peripheral!(AnyPin); + impl Pin for AnyPin {} impl sealed::Pin for AnyPin { fn pin_bank(&self) -> u8 { @@ -685,6 +679,12 @@ macro_rules! impl_pin { ($bank as u8) * 32 + $pin_num } } + + impl From for crate::gpio::AnyPin { + fn from(val: peripherals::$name) -> Self { + crate::gpio::Pin::degrade(val) + } + } }; } diff --git a/embassy-rp/src/lib.rs b/embassy-rp/src/lib.rs index 7da0d30c1..44150be0d 100644 --- a/embassy-rp/src/lib.rs +++ b/embassy-rp/src/lib.rs @@ -17,7 +17,7 @@ mod reset; // Reexports pub use embassy_cortex_m::executor; -pub use embassy_hal_common::{unborrow, Unborrow}; +pub use embassy_hal_common::{into_ref, Peripheral, PeripheralRef}; pub use embassy_macros::cortex_m_interrupt as interrupt; #[cfg(feature = "unstable-pac")] pub use rp2040_pac2 as pac; diff --git a/embassy-rp/src/spi.rs b/embassy-rp/src/spi.rs index 6b3f2238a..d0261598e 100644 --- a/embassy-rp/src/spi.rs +++ b/embassy-rp/src/spi.rs @@ -1,12 +1,10 @@ -use core::marker::PhantomData; - use embassy_embedded_hal::SetConfig; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; pub use embedded_hal_02::spi::{Phase, Polarity}; use crate::gpio::sealed::Pin as _; use crate::gpio::{AnyPin, Pin as GpioPin}; -use crate::{pac, peripherals, Unborrow}; +use crate::{pac, peripherals, Peripheral}; #[derive(Debug, Clone, Copy, PartialEq, Eq)] #[cfg_attr(feature = "defmt", derive(defmt::Format))] @@ -33,8 +31,7 @@ impl Default for Config { } pub struct Spi<'d, T: Instance> { - inner: T, - phantom: PhantomData<&'d mut T>, + inner: PeripheralRef<'d, T>, } fn div_roundup(a: u32, b: u32) -> u32 { @@ -62,52 +59,52 @@ fn calc_prescs(freq: u32) -> (u8, u8) { impl<'d, T: Instance> Spi<'d, T> { pub fn new( - inner: impl Unborrow + 'd, - clk: impl Unborrow> + 'd, - mosi: impl Unborrow> + 'd, - miso: impl Unborrow> + 'd, + inner: impl Peripheral

+ 'd, + clk: impl Peripheral

+ 'd> + 'd, + mosi: impl Peripheral

+ 'd> + 'd, + miso: impl Peripheral

+ 'd> + 'd, config: Config, ) -> Self { - unborrow!(clk, mosi, miso); + into_ref!(clk, mosi, miso); Self::new_inner( inner, - Some(clk.degrade()), - Some(mosi.degrade()), - Some(miso.degrade()), + Some(clk.map_into()), + Some(mosi.map_into()), + Some(miso.map_into()), None, config, ) } pub fn new_txonly( - inner: impl Unborrow + 'd, - clk: impl Unborrow> + 'd, - mosi: impl Unborrow> + 'd, + inner: impl Peripheral

+ 'd, + clk: impl Peripheral

+ 'd> + 'd, + mosi: impl Peripheral

+ 'd> + 'd, config: Config, ) -> Self { - unborrow!(clk, mosi); - Self::new_inner(inner, Some(clk.degrade()), Some(mosi.degrade()), None, None, config) + into_ref!(clk, mosi); + Self::new_inner(inner, Some(clk.map_into()), Some(mosi.map_into()), None, None, config) } pub fn new_rxonly( - inner: impl Unborrow + 'd, - clk: impl Unborrow> + 'd, - miso: impl Unborrow> + 'd, + inner: impl Peripheral

+ 'd, + clk: impl Peripheral

+ 'd> + 'd, + miso: impl Peripheral

+ 'd> + 'd, config: Config, ) -> Self { - unborrow!(clk, miso); - Self::new_inner(inner, Some(clk.degrade()), None, Some(miso.degrade()), None, config) + into_ref!(clk, miso); + Self::new_inner(inner, Some(clk.map_into()), None, Some(miso.map_into()), None, config) } fn new_inner( - inner: impl Unborrow + 'd, - clk: Option, - mosi: Option, - miso: Option, - cs: Option, + inner: impl Peripheral

+ 'd, + clk: Option>, + mosi: Option>, + miso: Option>, + cs: Option>, config: Config, ) -> Self { - unborrow!(inner); + into_ref!(inner); unsafe { let p = inner.regs(); @@ -137,10 +134,7 @@ impl<'d, T: Instance> Spi<'d, T> { pin.io().ctrl().write(|w| w.set_funcsel(1)); } } - Self { - inner, - phantom: PhantomData, - } + Self { inner } } pub fn blocking_write(&mut self, data: &[u8]) -> Result<(), Error> { diff --git a/embassy-rp/src/uart.rs b/embassy-rp/src/uart.rs index c95407b6f..b19f043f8 100644 --- a/embassy-rp/src/uart.rs +++ b/embassy-rp/src/uart.rs @@ -1,9 +1,7 @@ -use core::marker::PhantomData; - -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use gpio::Pin; -use crate::{gpio, pac, peripherals, Unborrow}; +use crate::{gpio, pac, peripherals, Peripheral}; #[non_exhaustive] pub struct Config { @@ -23,20 +21,19 @@ impl Default for Config { } pub struct Uart<'d, T: Instance> { - inner: T, - phantom: PhantomData<&'d mut T>, + inner: PeripheralRef<'d, T>, } impl<'d, T: Instance> Uart<'d, T> { pub fn new( - inner: impl Unborrow + 'd, - tx: impl Unborrow> + 'd, - rx: impl Unborrow> + 'd, - cts: impl Unborrow> + 'd, - rts: impl Unborrow> + 'd, + inner: impl Peripheral

+ 'd, + tx: impl Peripheral

> + 'd, + rx: impl Peripheral

> + 'd, + cts: impl Peripheral

> + 'd, + rts: impl Peripheral

> + 'd, config: Config, ) -> Self { - unborrow!(inner, tx, rx, cts, rts); + into_ref!(inner, tx, rx, cts, rts); unsafe { let p = inner.regs(); @@ -78,10 +75,7 @@ impl<'d, T: Instance> Uart<'d, T> { cts.io().ctrl().write(|w| w.set_funcsel(2)); rts.io().ctrl().write(|w| w.set_funcsel(2)); } - Self { - inner, - phantom: PhantomData, - } + Self { inner } } pub fn send(&mut self, data: &[u8]) { diff --git a/embassy-stm32/src/adc/f1.rs b/embassy-stm32/src/adc/f1.rs index 74cfac136..50d4f9bf9 100644 --- a/embassy-stm32/src/adc/f1.rs +++ b/embassy-stm32/src/adc/f1.rs @@ -1,12 +1,12 @@ use core::marker::PhantomData; -use embassy_hal_common::unborrow; +use embassy_hal_common::into_ref; use embedded_hal_02::blocking::delay::DelayUs; use crate::adc::{AdcPin, Instance}; use crate::rcc::get_freqs; use crate::time::Hertz; -use crate::Unborrow; +use crate::Peripheral; pub const VDDA_CALIB_MV: u32 = 3300; pub const ADC_MAX: u32 = (1 << 12) - 1; @@ -91,8 +91,8 @@ pub struct Adc<'d, T: Instance> { } impl<'d, T: Instance> Adc<'d, T> { - pub fn new(_peri: impl Unborrow + 'd, delay: &mut impl DelayUs) -> Self { - unborrow!(_peri); + pub fn new(_peri: impl Peripheral

+ 'd, delay: &mut impl DelayUs) -> Self { + into_ref!(_peri); T::enable(); T::reset(); unsafe { diff --git a/embassy-stm32/src/adc/v2.rs b/embassy-stm32/src/adc/v2.rs index 936a35562..5c608451b 100644 --- a/embassy-stm32/src/adc/v2.rs +++ b/embassy-stm32/src/adc/v2.rs @@ -1,11 +1,11 @@ use core::marker::PhantomData; -use embassy_hal_common::unborrow; +use embassy_hal_common::into_ref; use embedded_hal_02::blocking::delay::DelayUs; use crate::adc::{AdcPin, Instance}; use crate::time::Hertz; -use crate::Unborrow; +use crate::Peripheral; pub const VDDA_CALIB_MV: u32 = 3000; @@ -159,8 +159,8 @@ impl<'d, T> Adc<'d, T> where T: Instance, { - pub fn new(_peri: impl Unborrow + 'd, delay: &mut impl DelayUs) -> Self { - unborrow!(_peri); + pub fn new(_peri: impl Peripheral

+ 'd, delay: &mut impl DelayUs) -> Self { + into_ref!(_peri); enable(); let presc = unsafe { Prescaler::from_pclk2(crate::rcc::get_freqs().apb2) }; diff --git a/embassy-stm32/src/adc/v3.rs b/embassy-stm32/src/adc/v3.rs index 49d149b18..dbfd18810 100644 --- a/embassy-stm32/src/adc/v3.rs +++ b/embassy-stm32/src/adc/v3.rs @@ -1,10 +1,10 @@ use core::marker::PhantomData; -use embassy_hal_common::unborrow; +use embassy_hal_common::into_ref; use embedded_hal_02::blocking::delay::DelayUs; use crate::adc::{AdcPin, Instance}; -use crate::Unborrow; +use crate::Peripheral; pub const VDDA_CALIB_MV: u32 = 3000; @@ -208,8 +208,8 @@ pub struct Adc<'d, T: Instance> { } impl<'d, T: Instance> Adc<'d, T> { - pub fn new(_peri: impl Unborrow + 'd, delay: &mut impl DelayUs) -> Self { - unborrow!(_peri); + pub fn new(_peri: impl Peripheral

+ 'd, delay: &mut impl DelayUs) -> Self { + into_ref!(_peri); enable(); unsafe { T::regs().cr().modify(|reg| { diff --git a/embassy-stm32/src/adc/v4.rs b/embassy-stm32/src/adc/v4.rs index 3f933f4fc..92e8ac369 100644 --- a/embassy-stm32/src/adc/v4.rs +++ b/embassy-stm32/src/adc/v4.rs @@ -7,7 +7,7 @@ use pac::adccommon::vals::Presc; use super::{AdcPin, Instance}; use crate::time::Hertz; -use crate::{pac, Unborrow}; +use crate::{pac, Peripheral}; pub enum Resolution { SixteenBit, @@ -322,8 +322,8 @@ pub struct Adc<'d, T: Instance> { } impl<'d, T: Instance + crate::rcc::RccPeripheral> Adc<'d, T> { - pub fn new(_peri: impl Unborrow + 'd, delay: &mut impl DelayUs) -> Self { - embassy_hal_common::unborrow!(_peri); + pub fn new(_peri: impl Peripheral

+ 'd, delay: &mut impl DelayUs) -> Self { + embassy_hal_common::into_ref!(_peri); T::enable(); T::reset(); diff --git a/embassy-stm32/src/can/bxcan.rs b/embassy-stm32/src/can/bxcan.rs index b54fd3ff3..c0bd44e0f 100644 --- a/embassy-stm32/src/can/bxcan.rs +++ b/embassy-stm32/src/can/bxcan.rs @@ -1,25 +1,23 @@ -use core::marker::PhantomData; use core::ops::{Deref, DerefMut}; pub use bxcan; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use crate::gpio::sealed::AFType; use crate::rcc::RccPeripheral; -use crate::{peripherals, Unborrow}; +use crate::{peripherals, Peripheral}; -pub struct Can<'d, T: Instance + bxcan::Instance> { - phantom: PhantomData<&'d mut T>, - can: bxcan::Can, +pub struct Can<'d, T: Instance> { + can: bxcan::Can>, } -impl<'d, T: Instance + bxcan::Instance> Can<'d, T> { +impl<'d, T: Instance> Can<'d, T> { pub fn new( - peri: impl Unborrow + 'd, - rx: impl Unborrow> + 'd, - tx: impl Unborrow> + 'd, + peri: impl Peripheral

+ 'd, + rx: impl Peripheral

> + 'd, + tx: impl Peripheral

> + 'd, ) -> Self { - unborrow!(peri, rx, tx); + into_ref!(peri, rx, tx); unsafe { rx.set_as_af(rx.af_num(), AFType::Input); @@ -30,32 +28,29 @@ impl<'d, T: Instance + bxcan::Instance> Can<'d, T> { T::reset(); Self { - phantom: PhantomData, - can: bxcan::Can::builder(peri).enable(), + can: bxcan::Can::builder(BxcanInstance(peri)).enable(), } } } -impl<'d, T: Instance + bxcan::Instance> Drop for Can<'d, T> { +impl<'d, T: Instance> Drop for Can<'d, T> { fn drop(&mut self) { // Cannot call `free()` because it moves the instance. // Manually reset the peripheral. - unsafe { - T::regs().mcr().write(|w| w.set_reset(true)); - } + unsafe { T::regs().mcr().write(|w| w.set_reset(true)) } T::disable(); } } -impl<'d, T: Instance + bxcan::Instance> Deref for Can<'d, T> { - type Target = bxcan::Can; +impl<'d, T: Instance> Deref for Can<'d, T> { + type Target = bxcan::Can>; fn deref(&self) -> &Self::Target { &self.can } } -impl<'d, T: Instance + bxcan::Instance> DerefMut for Can<'d, T> { +impl<'d, T: Instance> DerefMut for Can<'d, T> { fn deref_mut(&mut self) -> &mut Self::Target { &mut self.can } @@ -63,15 +58,25 @@ impl<'d, T: Instance + bxcan::Instance> DerefMut for Can<'d, T> { pub(crate) mod sealed { pub trait Instance { + const REGISTERS: *mut bxcan::RegisterBlock; + fn regs() -> &'static crate::pac::can::Can; } } pub trait Instance: sealed::Instance + RccPeripheral {} +pub struct BxcanInstance<'a, T>(PeripheralRef<'a, T>); + +unsafe impl<'d, T: Instance> bxcan::Instance for BxcanInstance<'d, T> { + const REGISTERS: *mut bxcan::RegisterBlock = T::REGISTERS; +} + foreach_peripheral!( (can, $inst:ident) => { impl sealed::Instance for peripherals::$inst { + const REGISTERS: *mut bxcan::RegisterBlock = crate::pac::$inst.0 as *mut _; + fn regs() -> &'static crate::pac::can::Can { &crate::pac::$inst } @@ -79,15 +84,12 @@ foreach_peripheral!( impl Instance for peripherals::$inst {} - unsafe impl bxcan::Instance for peripherals::$inst { - const REGISTERS: *mut bxcan::RegisterBlock = crate::pac::$inst.0 as *mut _; - } }; ); foreach_peripheral!( (can, CAN) => { - unsafe impl bxcan::FilterOwner for peripherals::CAN { + unsafe impl<'d> bxcan::FilterOwner for BxcanInstance<'d, peripherals::CAN> { const NUM_FILTER_BANKS: u8 = 14; } }; @@ -102,19 +104,19 @@ foreach_peripheral!( ))] { // Most L4 devices and some F7 devices use the name "CAN1" // even if there is no "CAN2" peripheral. - unsafe impl bxcan::FilterOwner for peripherals::CAN1 { + unsafe impl<'d> bxcan::FilterOwner for BxcanInstance<'d, peripherals::CAN1> { const NUM_FILTER_BANKS: u8 = 14; } } else { - unsafe impl bxcan::FilterOwner for peripherals::CAN1 { + unsafe impl<'d> bxcan::FilterOwner for BxcanInstance<'d, peripherals::CAN1> { const NUM_FILTER_BANKS: u8 = 28; } - unsafe impl bxcan::MasterInstance for peripherals::CAN1 {} + unsafe impl<'d> bxcan::MasterInstance for BxcanInstance<'d, peripherals::CAN1> {} } } }; (can, CAN3) => { - unsafe impl bxcan::FilterOwner for peripherals::CAN3 { + unsafe impl<'d> bxcan::FilterOwner for BxcanInstance<'d, peripherals::CAN3> { const NUM_FILTER_BANKS: u8 = 14; } }; diff --git a/embassy-stm32/src/crc/v1.rs b/embassy-stm32/src/crc/v1.rs index 87133714c..393089eed 100644 --- a/embassy-stm32/src/crc/v1.rs +++ b/embassy-stm32/src/crc/v1.rs @@ -1,31 +1,26 @@ -use core::marker::PhantomData; - -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use crate::pac::CRC as PAC_CRC; use crate::peripherals::CRC; use crate::rcc::sealed::RccPeripheral; -use crate::Unborrow; +use crate::Peripheral; pub struct Crc<'d> { - _peripheral: CRC, - _phantom: PhantomData<&'d mut CRC>, + _peri: PeripheralRef<'d, CRC>, } impl<'d> Crc<'d> { /// Instantiates the CRC32 peripheral and initializes it to default values. - pub fn new(peripheral: impl Unborrow + 'd) -> Self { + pub fn new(peripheral: impl Peripheral

+ 'd) -> Self { + into_ref!(peripheral); + // Note: enable and reset come from RccPeripheral. // enable CRC clock in RCC. CRC::enable(); // Reset CRC to default values. CRC::reset(); - // Unborrow the peripheral - unborrow!(peripheral); - let mut instance = Self { - _peripheral: peripheral, - _phantom: PhantomData, - }; + // Peripheral the peripheral + let mut instance = Self { _peri: peripheral }; instance.reset(); instance } diff --git a/embassy-stm32/src/crc/v2v3.rs b/embassy-stm32/src/crc/v2v3.rs index 63f24e4e1..8acb3a770 100644 --- a/embassy-stm32/src/crc/v2v3.rs +++ b/embassy-stm32/src/crc/v2v3.rs @@ -1,16 +1,13 @@ -use core::marker::PhantomData; - -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use crate::pac::crc::vals; use crate::pac::CRC as PAC_CRC; use crate::peripherals::CRC; use crate::rcc::sealed::RccPeripheral; -use crate::Unborrow; +use crate::Peripheral; pub struct Crc<'d> { - _peripheral: CRC, - _phantom: PhantomData<&'d mut CRC>, + _peripheral: PeripheralRef<'d, CRC>, _config: Config, } @@ -70,16 +67,15 @@ pub enum PolySize { impl<'d> Crc<'d> { /// Instantiates the CRC32 peripheral and initializes it to default values. - pub fn new(peripheral: impl Unborrow + 'd, config: Config) -> Self { + pub fn new(peripheral: impl Peripheral

+ 'd, config: Config) -> Self { // Note: enable and reset come from RccPeripheral. // enable CRC clock in RCC. CRC::enable(); // Reset CRC to default values. CRC::reset(); - unborrow!(peripheral); + into_ref!(peripheral); let mut instance = Self { _peripheral: peripheral, - _phantom: PhantomData, _config: config, }; CRC::reset(); diff --git a/embassy-stm32/src/dac/v2.rs b/embassy-stm32/src/dac/v2.rs index ba7856a5a..6b7f41c63 100644 --- a/embassy-stm32/src/dac/v2.rs +++ b/embassy-stm32/src/dac/v2.rs @@ -1,10 +1,8 @@ -use core::marker::PhantomData; - -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use crate::dac::{DacPin, Instance}; use crate::pac::dac; -use crate::Unborrow; +use crate::Peripheral; #[derive(Debug, Copy, Clone, Eq, PartialEq)] #[cfg_attr(feature = "defmt", derive(defmt::Format))] @@ -90,7 +88,7 @@ pub enum Value { pub struct Dac<'d, T: Instance> { channels: u8, - phantom: PhantomData<&'d mut T>, + _peri: PeripheralRef<'d, T>, } macro_rules! enable { @@ -102,21 +100,21 @@ macro_rules! enable { } impl<'d, T: Instance> Dac<'d, T> { - pub fn new_1ch(peri: impl Unborrow + 'd, _ch1: impl Unborrow> + 'd) -> Self { - unborrow!(peri); + pub fn new_1ch(peri: impl Peripheral

+ 'd, _ch1: impl Peripheral

> + 'd) -> Self { + into_ref!(peri); Self::new_inner(peri, 1) } pub fn new_2ch( - peri: impl Unborrow + 'd, - _ch1: impl Unborrow> + 'd, - _ch2: impl Unborrow> + 'd, + peri: impl Peripheral

+ 'd, + _ch1: impl Peripheral

> + 'd, + _ch2: impl Peripheral

> + 'd, ) -> Self { - unborrow!(peri); + into_ref!(peri); Self::new_inner(peri, 2) } - fn new_inner(_peri: T, channels: u8) -> Self { + fn new_inner(peri: PeripheralRef<'d, T>, channels: u8) -> Self { unsafe { // Sadly we cannot use `RccPeripheral::enable` since devices are quite inconsistent DAC clock // configuration. @@ -144,10 +142,7 @@ impl<'d, T: Instance> Dac<'d, T> { } } - Self { - channels, - phantom: PhantomData, - } + Self { channels, _peri: peri } } /// Check the channel is configured diff --git a/embassy-stm32/src/dcmi.rs b/embassy-stm32/src/dcmi.rs index f4ca93a71..e28225426 100644 --- a/embassy-stm32/src/dcmi.rs +++ b/embassy-stm32/src/dcmi.rs @@ -1,14 +1,13 @@ -use core::marker::PhantomData; use core::task::Poll; use embassy::waitqueue::AtomicWaker; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use futures::future::poll_fn; use crate::gpio::sealed::AFType; use crate::gpio::Speed; use crate::interrupt::{Interrupt, InterruptExt}; -use crate::Unborrow; +use crate::Peripheral; /// The level on the VSync pin when the data is not valid on the parallel interface. #[derive(Clone, Copy, PartialEq)] @@ -70,7 +69,7 @@ impl Default for Config { macro_rules! config_pins { ($($pin:ident),*) => { - unborrow!($($pin),*); + into_ref!($($pin),*); // NOTE(unsafe) Exclusive access to the registers critical_section::with(|_| unsafe { $( @@ -82,9 +81,8 @@ macro_rules! config_pins { } pub struct Dcmi<'d, T: Instance, Dma: FrameDma> { - inner: T, - dma: Dma, - phantom: PhantomData<&'d mut T>, + inner: PeripheralRef<'d, T>, + dma: PeripheralRef<'d, Dma>, } impl<'d, T, Dma> Dcmi<'d, T, Dma> @@ -93,23 +91,23 @@ where Dma: FrameDma, { pub fn new_8bit( - peri: impl Unborrow + 'd, - dma: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - d0: impl Unborrow> + 'd, - d1: impl Unborrow> + 'd, - d2: impl Unborrow> + 'd, - d3: impl Unborrow> + 'd, - d4: impl Unborrow> + 'd, - d5: impl Unborrow> + 'd, - d6: impl Unborrow> + 'd, - d7: impl Unborrow> + 'd, - v_sync: impl Unborrow> + 'd, - h_sync: impl Unborrow> + 'd, - pixclk: impl Unborrow> + 'd, + peri: impl Peripheral

+ 'd, + dma: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + d0: impl Peripheral

> + 'd, + d1: impl Peripheral

> + 'd, + d2: impl Peripheral

> + 'd, + d3: impl Peripheral

> + 'd, + d4: impl Peripheral

> + 'd, + d5: impl Peripheral

> + 'd, + d6: impl Peripheral

> + 'd, + d7: impl Peripheral

> + 'd, + v_sync: impl Peripheral

> + 'd, + h_sync: impl Peripheral

> + 'd, + pixclk: impl Peripheral

> + 'd, config: Config, ) -> Self { - unborrow!(peri, dma, irq); + into_ref!(peri, dma, irq); config_pins!(d0, d1, d2, d3, d4, d5, d6, d7); config_pins!(v_sync, h_sync, pixclk); @@ -117,25 +115,25 @@ where } pub fn new_10bit( - peri: impl Unborrow + 'd, - dma: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - d0: impl Unborrow> + 'd, - d1: impl Unborrow> + 'd, - d2: impl Unborrow> + 'd, - d3: impl Unborrow> + 'd, - d4: impl Unborrow> + 'd, - d5: impl Unborrow> + 'd, - d6: impl Unborrow> + 'd, - d7: impl Unborrow> + 'd, - d8: impl Unborrow> + 'd, - d9: impl Unborrow> + 'd, - v_sync: impl Unborrow> + 'd, - h_sync: impl Unborrow> + 'd, - pixclk: impl Unborrow> + 'd, + peri: impl Peripheral

+ 'd, + dma: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + d0: impl Peripheral

> + 'd, + d1: impl Peripheral

> + 'd, + d2: impl Peripheral

> + 'd, + d3: impl Peripheral

> + 'd, + d4: impl Peripheral

> + 'd, + d5: impl Peripheral

> + 'd, + d6: impl Peripheral

> + 'd, + d7: impl Peripheral

> + 'd, + d8: impl Peripheral

> + 'd, + d9: impl Peripheral

> + 'd, + v_sync: impl Peripheral

> + 'd, + h_sync: impl Peripheral

> + 'd, + pixclk: impl Peripheral

> + 'd, config: Config, ) -> Self { - unborrow!(peri, dma, irq); + into_ref!(peri, dma, irq); config_pins!(d0, d1, d2, d3, d4, d5, d6, d7, d8, d9); config_pins!(v_sync, h_sync, pixclk); @@ -143,27 +141,27 @@ where } pub fn new_12bit( - peri: impl Unborrow + 'd, - dma: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - d0: impl Unborrow> + 'd, - d1: impl Unborrow> + 'd, - d2: impl Unborrow> + 'd, - d3: impl Unborrow> + 'd, - d4: impl Unborrow> + 'd, - d5: impl Unborrow> + 'd, - d6: impl Unborrow> + 'd, - d7: impl Unborrow> + 'd, - d8: impl Unborrow> + 'd, - d9: impl Unborrow> + 'd, - d10: impl Unborrow> + 'd, - d11: impl Unborrow> + 'd, - v_sync: impl Unborrow> + 'd, - h_sync: impl Unborrow> + 'd, - pixclk: impl Unborrow> + 'd, + peri: impl Peripheral

+ 'd, + dma: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + d0: impl Peripheral

> + 'd, + d1: impl Peripheral

> + 'd, + d2: impl Peripheral

> + 'd, + d3: impl Peripheral

> + 'd, + d4: impl Peripheral

> + 'd, + d5: impl Peripheral

> + 'd, + d6: impl Peripheral

> + 'd, + d7: impl Peripheral

> + 'd, + d8: impl Peripheral

> + 'd, + d9: impl Peripheral

> + 'd, + d10: impl Peripheral

> + 'd, + d11: impl Peripheral

> + 'd, + v_sync: impl Peripheral

> + 'd, + h_sync: impl Peripheral

> + 'd, + pixclk: impl Peripheral

> + 'd, config: Config, ) -> Self { - unborrow!(peri, dma, irq); + into_ref!(peri, dma, irq); config_pins!(d0, d1, d2, d3, d4, d5, d6, d7, d8, d9, d10, d11); config_pins!(v_sync, h_sync, pixclk); @@ -171,29 +169,29 @@ where } pub fn new_14bit( - peri: impl Unborrow + 'd, - dma: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - d0: impl Unborrow> + 'd, - d1: impl Unborrow> + 'd, - d2: impl Unborrow> + 'd, - d3: impl Unborrow> + 'd, - d4: impl Unborrow> + 'd, - d5: impl Unborrow> + 'd, - d6: impl Unborrow> + 'd, - d7: impl Unborrow> + 'd, - d8: impl Unborrow> + 'd, - d9: impl Unborrow> + 'd, - d10: impl Unborrow> + 'd, - d11: impl Unborrow> + 'd, - d12: impl Unborrow> + 'd, - d13: impl Unborrow> + 'd, - v_sync: impl Unborrow> + 'd, - h_sync: impl Unborrow> + 'd, - pixclk: impl Unborrow> + 'd, + peri: impl Peripheral

+ 'd, + dma: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + d0: impl Peripheral

> + 'd, + d1: impl Peripheral

> + 'd, + d2: impl Peripheral

> + 'd, + d3: impl Peripheral

> + 'd, + d4: impl Peripheral

> + 'd, + d5: impl Peripheral

> + 'd, + d6: impl Peripheral

> + 'd, + d7: impl Peripheral

> + 'd, + d8: impl Peripheral

> + 'd, + d9: impl Peripheral

> + 'd, + d10: impl Peripheral

> + 'd, + d11: impl Peripheral

> + 'd, + d12: impl Peripheral

> + 'd, + d13: impl Peripheral

> + 'd, + v_sync: impl Peripheral

> + 'd, + h_sync: impl Peripheral

> + 'd, + pixclk: impl Peripheral

> + 'd, config: Config, ) -> Self { - unborrow!(peri, dma, irq); + into_ref!(peri, dma, irq); config_pins!(d0, d1, d2, d3, d4, d5, d6, d7, d8, d9, d10, d11, d12, d13); config_pins!(v_sync, h_sync, pixclk); @@ -201,21 +199,21 @@ where } pub fn new_es_8bit( - peri: impl Unborrow + 'd, - dma: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - d0: impl Unborrow> + 'd, - d1: impl Unborrow> + 'd, - d2: impl Unborrow> + 'd, - d3: impl Unborrow> + 'd, - d4: impl Unborrow> + 'd, - d5: impl Unborrow> + 'd, - d6: impl Unborrow> + 'd, - d7: impl Unborrow> + 'd, - pixclk: impl Unborrow> + 'd, + peri: impl Peripheral

+ 'd, + dma: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + d0: impl Peripheral

> + 'd, + d1: impl Peripheral

> + 'd, + d2: impl Peripheral

> + 'd, + d3: impl Peripheral

> + 'd, + d4: impl Peripheral

> + 'd, + d5: impl Peripheral

> + 'd, + d6: impl Peripheral

> + 'd, + d7: impl Peripheral

> + 'd, + pixclk: impl Peripheral

> + 'd, config: Config, ) -> Self { - unborrow!(peri, dma, irq); + into_ref!(peri, dma, irq); config_pins!(d0, d1, d2, d3, d4, d5, d6, d7); config_pins!(pixclk); @@ -223,23 +221,23 @@ where } pub fn new_es_10bit( - peri: impl Unborrow + 'd, - dma: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - d0: impl Unborrow> + 'd, - d1: impl Unborrow> + 'd, - d2: impl Unborrow> + 'd, - d3: impl Unborrow> + 'd, - d4: impl Unborrow> + 'd, - d5: impl Unborrow> + 'd, - d6: impl Unborrow> + 'd, - d7: impl Unborrow> + 'd, - d8: impl Unborrow> + 'd, - d9: impl Unborrow> + 'd, - pixclk: impl Unborrow> + 'd, + peri: impl Peripheral

+ 'd, + dma: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + d0: impl Peripheral

> + 'd, + d1: impl Peripheral

> + 'd, + d2: impl Peripheral

> + 'd, + d3: impl Peripheral

> + 'd, + d4: impl Peripheral

> + 'd, + d5: impl Peripheral

> + 'd, + d6: impl Peripheral

> + 'd, + d7: impl Peripheral

> + 'd, + d8: impl Peripheral

> + 'd, + d9: impl Peripheral

> + 'd, + pixclk: impl Peripheral

> + 'd, config: Config, ) -> Self { - unborrow!(peri, dma, irq); + into_ref!(peri, dma, irq); config_pins!(d0, d1, d2, d3, d4, d5, d6, d7, d8, d9); config_pins!(pixclk); @@ -247,25 +245,25 @@ where } pub fn new_es_12bit( - peri: impl Unborrow + 'd, - dma: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - d0: impl Unborrow> + 'd, - d1: impl Unborrow> + 'd, - d2: impl Unborrow> + 'd, - d3: impl Unborrow> + 'd, - d4: impl Unborrow> + 'd, - d5: impl Unborrow> + 'd, - d6: impl Unborrow> + 'd, - d7: impl Unborrow> + 'd, - d8: impl Unborrow> + 'd, - d9: impl Unborrow> + 'd, - d10: impl Unborrow> + 'd, - d11: impl Unborrow> + 'd, - pixclk: impl Unborrow> + 'd, + peri: impl Peripheral

+ 'd, + dma: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + d0: impl Peripheral

> + 'd, + d1: impl Peripheral

> + 'd, + d2: impl Peripheral

> + 'd, + d3: impl Peripheral

> + 'd, + d4: impl Peripheral

> + 'd, + d5: impl Peripheral

> + 'd, + d6: impl Peripheral

> + 'd, + d7: impl Peripheral

> + 'd, + d8: impl Peripheral

> + 'd, + d9: impl Peripheral

> + 'd, + d10: impl Peripheral

> + 'd, + d11: impl Peripheral

> + 'd, + pixclk: impl Peripheral

> + 'd, config: Config, ) -> Self { - unborrow!(peri, dma, irq); + into_ref!(peri, dma, irq); config_pins!(d0, d1, d2, d3, d4, d5, d6, d7, d8, d9, d10, d11); config_pins!(pixclk); @@ -273,27 +271,27 @@ where } pub fn new_es_14bit( - peri: impl Unborrow + 'd, - dma: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - d0: impl Unborrow> + 'd, - d1: impl Unborrow> + 'd, - d2: impl Unborrow> + 'd, - d3: impl Unborrow> + 'd, - d4: impl Unborrow> + 'd, - d5: impl Unborrow> + 'd, - d6: impl Unborrow> + 'd, - d7: impl Unborrow> + 'd, - d8: impl Unborrow> + 'd, - d9: impl Unborrow> + 'd, - d10: impl Unborrow> + 'd, - d11: impl Unborrow> + 'd, - d12: impl Unborrow> + 'd, - d13: impl Unborrow> + 'd, - pixclk: impl Unborrow> + 'd, + peri: impl Peripheral

+ 'd, + dma: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + d0: impl Peripheral

> + 'd, + d1: impl Peripheral

> + 'd, + d2: impl Peripheral

> + 'd, + d3: impl Peripheral

> + 'd, + d4: impl Peripheral

> + 'd, + d5: impl Peripheral

> + 'd, + d6: impl Peripheral

> + 'd, + d7: impl Peripheral

> + 'd, + d8: impl Peripheral

> + 'd, + d9: impl Peripheral

> + 'd, + d10: impl Peripheral

> + 'd, + d11: impl Peripheral

> + 'd, + d12: impl Peripheral

> + 'd, + d13: impl Peripheral

> + 'd, + pixclk: impl Peripheral

> + 'd, config: Config, ) -> Self { - unborrow!(peri, dma, irq); + into_ref!(peri, dma, irq); config_pins!(d0, d1, d2, d3, d4, d5, d6, d7, d8, d9, d10, d11, d12, d13); config_pins!(pixclk); @@ -301,9 +299,9 @@ where } fn new_inner( - peri: T, - dma: Dma, - irq: T::Interrupt, + peri: PeripheralRef<'d, T>, + dma: PeripheralRef<'d, Dma>, + irq: PeripheralRef<'d, T::Interrupt>, config: Config, use_embedded_synchronization: bool, edm: u8, @@ -327,11 +325,7 @@ where irq.unpend(); irq.enable(); - Self { - inner: peri, - dma, - phantom: PhantomData, - } + Self { inner: peri, dma } } unsafe fn on_interrupt(_: *mut ()) { diff --git a/embassy-stm32/src/dma/mod.rs b/embassy-stm32/src/dma/mod.rs index 87ac38ba8..cc030a93e 100644 --- a/embassy-stm32/src/dma/mod.rs +++ b/embassy-stm32/src/dma/mod.rs @@ -8,16 +8,15 @@ mod dmamux; mod gpdma; use core::future::Future; -use core::marker::PhantomData; use core::mem; use core::pin::Pin; use core::task::{Context, Poll, Waker}; -#[cfg(dmamux)] -pub use dmamux::*; -use embassy_hal_common::unborrow; +use embassy_hal_common::{impl_peripheral, into_ref}; -use crate::Unborrow; +#[cfg(dmamux)] +pub use self::dmamux::*; +use crate::Peripheral; #[cfg(feature = "unstable-pac")] pub mod low_level { @@ -207,17 +206,19 @@ impl Default for TransferOptions { } mod transfers { + use embassy_hal_common::PeripheralRef; + use super::*; #[allow(unused)] pub fn read<'a, W: Word>( - channel: impl Unborrow + 'a, + channel: impl Peripheral

+ 'a, request: Request, reg_addr: *mut W, buf: &'a mut [W], ) -> impl Future + 'a { assert!(buf.len() > 0 && buf.len() <= 0xFFFF); - unborrow!(channel); + into_ref!(channel); unsafe { channel.start_read::(request, reg_addr, buf, Default::default()) }; @@ -226,13 +227,13 @@ mod transfers { #[allow(unused)] pub fn write<'a, W: Word>( - channel: impl Unborrow + 'a, + channel: impl Peripheral

+ 'a, request: Request, buf: &'a [W], reg_addr: *mut W, ) -> impl Future + 'a { assert!(buf.len() > 0 && buf.len() <= 0xFFFF); - unborrow!(channel); + into_ref!(channel); unsafe { channel.start_write::(request, buf, reg_addr, Default::default()) }; @@ -241,13 +242,13 @@ mod transfers { #[allow(unused)] pub fn write_repeated<'a, W: Word>( - channel: impl Unborrow + 'a, + channel: impl Peripheral

+ 'a, request: Request, repeated: W, count: usize, reg_addr: *mut W, ) -> impl Future + 'a { - unborrow!(channel); + into_ref!(channel); unsafe { channel.start_write_repeated::(request, repeated, count, reg_addr, Default::default()) }; @@ -255,17 +256,13 @@ mod transfers { } pub(crate) struct Transfer<'a, C: Channel> { - channel: C, - _phantom: PhantomData<&'a mut C>, + channel: PeripheralRef<'a, C>, } impl<'a, C: Channel> Transfer<'a, C> { - pub(crate) fn new(channel: impl Unborrow + 'a) -> Self { - unborrow!(channel); - Self { - channel, - _phantom: PhantomData, - } + pub(crate) fn new(channel: impl Peripheral

+ 'a) -> Self { + into_ref!(channel); + Self { channel } } } @@ -290,17 +287,11 @@ mod transfers { } } -pub trait Channel: sealed::Channel + Unborrow + 'static {} +pub trait Channel: sealed::Channel + Peripheral

+ 'static {} pub struct NoDma; -unsafe impl Unborrow for NoDma { - type Target = NoDma; - - unsafe fn unborrow(self) -> Self::Target { - self - } -} +impl_peripheral!(NoDma); // safety: must be called only once at startup pub(crate) unsafe fn init() { diff --git a/embassy-stm32/src/eth/v1/mod.rs b/embassy-stm32/src/eth/v1/mod.rs index 7985acc5a..5e31c32b5 100644 --- a/embassy-stm32/src/eth/v1/mod.rs +++ b/embassy-stm32/src/eth/v1/mod.rs @@ -6,7 +6,7 @@ use core::task::Waker; use embassy::waitqueue::AtomicWaker; use embassy_cortex_m::peripheral::{PeripheralMutex, PeripheralState, StateStorage}; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use embassy_net::{Device, DeviceCapabilities, LinkState, PacketBuf, MTU}; use crate::gpio::sealed::{AFType, Pin as __GpioPin}; @@ -16,7 +16,7 @@ use crate::pac::AFIO; #[cfg(any(eth_v1b, eth_v1c))] use crate::pac::SYSCFG; use crate::pac::{ETH, RCC}; -use crate::Unborrow; +use crate::Peripheral; mod descriptors; mod rx_desc; @@ -36,7 +36,7 @@ impl<'d, T: Instance, const TX: usize, const RX: usize> State<'d, T, TX, RX> { pub struct Ethernet<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> { state: PeripheralMutex<'d, Inner<'d, T, TX, RX>>, - pins: [AnyPin; 9], + pins: [PeripheralRef<'d, AnyPin>; 9], _phy: P, clock_range: Cr, phy_addr: u8, @@ -86,22 +86,22 @@ impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> Ethernet<'d, T, /// safety: the returned instance is not leak-safe pub unsafe fn new( state: &'d mut State<'d, T, TX, RX>, - peri: impl Unborrow + 'd, - interrupt: impl Unborrow + 'd, - ref_clk: impl Unborrow> + 'd, - mdio: impl Unborrow> + 'd, - mdc: impl Unborrow> + 'd, - crs: impl Unborrow> + 'd, - rx_d0: impl Unborrow> + 'd, - rx_d1: impl Unborrow> + 'd, - tx_d0: impl Unborrow> + 'd, - tx_d1: impl Unborrow> + 'd, - tx_en: impl Unborrow> + 'd, + peri: impl Peripheral

+ 'd, + interrupt: impl Peripheral

+ 'd, + ref_clk: impl Peripheral

> + 'd, + mdio: impl Peripheral

> + 'd, + mdc: impl Peripheral

> + 'd, + crs: impl Peripheral

> + 'd, + rx_d0: impl Peripheral

> + 'd, + rx_d1: impl Peripheral

> + 'd, + tx_d0: impl Peripheral

> + 'd, + tx_d1: impl Peripheral

> + 'd, + tx_en: impl Peripheral

> + 'd, phy: P, mac_addr: [u8; 6], phy_addr: u8, ) -> Self { - unborrow!(interrupt, ref_clk, mdio, mdc, crs, rx_d0, rx_d1, tx_d0, tx_d1, tx_en); + into_ref!(interrupt, ref_clk, mdio, mdc, crs, rx_d0, rx_d1, tx_d0, tx_d1, tx_en); // Enable the necessary Clocks // NOTE(unsafe) We have exclusive access to the registers @@ -207,15 +207,15 @@ impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> Ethernet<'d, T, }; let pins = [ - ref_clk.degrade(), - mdio.degrade(), - mdc.degrade(), - crs.degrade(), - rx_d0.degrade(), - rx_d1.degrade(), - tx_d0.degrade(), - tx_d1.degrade(), - tx_en.degrade(), + 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 { @@ -370,7 +370,7 @@ struct Inner<'d, T: Instance, const TX: usize, const RX: usize> { } impl<'d, T: Instance, const TX: usize, const RX: usize> Inner<'d, T, TX, RX> { - pub fn new(_peri: impl Unborrow + 'd) -> Self { + pub fn new(_peri: impl Peripheral

+ 'd) -> Self { Self { _peri: PhantomData, desc_ring: DescriptorRing::new(), diff --git a/embassy-stm32/src/eth/v2/mod.rs b/embassy-stm32/src/eth/v2/mod.rs index 2b1caf992..2b4a9367b 100644 --- a/embassy-stm32/src/eth/v2/mod.rs +++ b/embassy-stm32/src/eth/v2/mod.rs @@ -4,13 +4,13 @@ use core::task::Waker; use embassy::waitqueue::AtomicWaker; use embassy_cortex_m::peripheral::{PeripheralMutex, PeripheralState, StateStorage}; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use embassy_net::{Device, DeviceCapabilities, LinkState, PacketBuf, MTU}; use crate::gpio::sealed::{AFType, Pin as _}; use crate::gpio::{AnyPin, Speed}; use crate::pac::{ETH, RCC, SYSCFG}; -use crate::Unborrow; +use crate::Peripheral; mod descriptors; use descriptors::DescriptorRing; @@ -25,7 +25,7 @@ impl<'d, T: Instance, const TX: usize, const RX: usize> State<'d, T, TX, RX> { } pub struct Ethernet<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> { state: PeripheralMutex<'d, Inner<'d, T, TX, RX>>, - pins: [AnyPin; 9], + pins: [PeripheralRef<'d, AnyPin>; 9], _phy: P, clock_range: u8, phy_addr: u8, @@ -48,22 +48,22 @@ impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> Ethernet<'d, T, /// safety: the returned instance is not leak-safe pub unsafe fn new( state: &'d mut State<'d, T, TX, RX>, - peri: impl Unborrow + 'd, - interrupt: impl Unborrow + 'd, - ref_clk: impl Unborrow> + 'd, - mdio: impl Unborrow> + 'd, - mdc: impl Unborrow> + 'd, - crs: impl Unborrow> + 'd, - rx_d0: impl Unborrow> + 'd, - rx_d1: impl Unborrow> + 'd, - tx_d0: impl Unborrow> + 'd, - tx_d1: impl Unborrow> + 'd, - tx_en: impl Unborrow> + 'd, + peri: impl Peripheral

+ 'd, + interrupt: impl Peripheral

+ 'd, + ref_clk: impl Peripheral

> + 'd, + mdio: impl Peripheral

> + 'd, + mdc: impl Peripheral

> + 'd, + crs: impl Peripheral

> + 'd, + rx_d0: impl Peripheral

> + 'd, + rx_d1: impl Peripheral

> + 'd, + tx_d0: impl Peripheral

> + 'd, + tx_d1: impl Peripheral

> + 'd, + tx_en: impl Peripheral

> + 'd, phy: P, mac_addr: [u8; 6], phy_addr: u8, ) -> Self { - unborrow!(interrupt, ref_clk, mdio, mdc, crs, rx_d0, rx_d1, tx_d0, tx_d1, tx_en); + into_ref!(interrupt, ref_clk, mdio, mdc, crs, rx_d0, rx_d1, tx_d0, tx_d1, tx_en); // Enable the necessary Clocks // NOTE(unsafe) We have exclusive access to the registers @@ -143,15 +143,15 @@ impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> Ethernet<'d, T, }; let pins = [ - ref_clk.degrade(), - mdio.degrade(), - mdc.degrade(), - crs.degrade(), - rx_d0.degrade(), - rx_d1.degrade(), - tx_d0.degrade(), - tx_d1.degrade(), - tx_en.degrade(), + 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 { @@ -316,7 +316,7 @@ struct Inner<'d, T: Instance, const TX: usize, const RX: usize> { } impl<'d, T: Instance, const TX: usize, const RX: usize> Inner<'d, T, TX, RX> { - pub fn new(_peri: impl Unborrow + 'd) -> Self { + pub fn new(_peri: impl Peripheral

+ 'd) -> Self { Self { _peri: PhantomData, desc_ring: DescriptorRing::new(), diff --git a/embassy-stm32/src/exti.rs b/embassy-stm32/src/exti.rs index 94e0e941d..3b8d9390f 100644 --- a/embassy-stm32/src/exti.rs +++ b/embassy-stm32/src/exti.rs @@ -4,12 +4,12 @@ use core::pin::Pin; use core::task::{Context, Poll}; use embassy::waitqueue::AtomicWaker; -use embassy_hal_common::unsafe_impl_unborrow; +use embassy_hal_common::impl_peripheral; use crate::gpio::{AnyPin, Input, Pin as GpioPin}; use crate::pac::exti::regs::Lines; use crate::pac::EXTI; -use crate::{interrupt, pac, peripherals, Unborrow}; +use crate::{interrupt, pac, peripherals, Peripheral}; const EXTI_COUNT: usize = 16; const NEW_AW: AtomicWaker = AtomicWaker::new(); @@ -86,7 +86,7 @@ pub struct ExtiInput<'d, T: GpioPin> { impl<'d, T: GpioPin> Unpin for ExtiInput<'d, T> {} impl<'d, T: GpioPin> ExtiInput<'d, T> { - pub fn new(pin: Input<'d, T>, _ch: impl Unborrow + 'd) -> Self { + pub fn new(pin: Input<'d, T>, _ch: impl Peripheral

+ 'd) -> Self { Self { pin } } @@ -320,7 +320,7 @@ pub trait Channel: sealed::Channel + Sized { pub struct AnyChannel { number: u8, } -unsafe_impl_unborrow!(AnyChannel); +impl_peripheral!(AnyChannel); impl sealed::Channel for AnyChannel {} impl Channel for AnyChannel { fn number(&self) -> usize { diff --git a/embassy-stm32/src/flash/mod.rs b/embassy-stm32/src/flash/mod.rs index 2047f70e1..5258c9b04 100644 --- a/embassy-stm32/src/flash/mod.rs +++ b/embassy-stm32/src/flash/mod.rs @@ -1,11 +1,9 @@ -use core::marker::PhantomData; - -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use embedded_storage::nor_flash::{ErrorType, NorFlash, NorFlashError, NorFlashErrorKind, ReadNorFlash}; pub use crate::pac::{ERASE_SIZE, ERASE_VALUE, FLASH_BASE, FLASH_SIZE, WRITE_SIZE}; use crate::peripherals::FLASH; -use crate::Unborrow; +use crate::Peripheral; const FLASH_END: usize = FLASH_BASE + FLASH_SIZE; #[cfg_attr(any(flash_wl, flash_wb, flash_l0, flash_l1, flash_l4), path = "l.rs")] @@ -16,20 +14,16 @@ const FLASH_END: usize = FLASH_BASE + FLASH_SIZE; mod family; pub struct Flash<'d> { - _inner: FLASH, - _phantom: PhantomData<&'d mut FLASH>, + _inner: PeripheralRef<'d, FLASH>, } impl<'d> Flash<'d> { - pub fn new(p: impl Unborrow) -> Self { - unborrow!(p); - Self { - _inner: p, - _phantom: PhantomData, - } + pub fn new(p: impl Peripheral

+ 'd) -> Self { + into_ref!(p); + Self { _inner: p } } - pub fn unlock(p: impl Unborrow) -> Self { + pub fn unlock(p: impl Peripheral

+ 'd) -> Self { let flash = Self::new(p); unsafe { family::unlock() }; diff --git a/embassy-stm32/src/fmc/mod.rs b/embassy-stm32/src/fmc/mod.rs index 4f8e467d0..856a4adca 100644 --- a/embassy-stm32/src/fmc/mod.rs +++ b/embassy-stm32/src/fmc/mod.rs @@ -1,10 +1,10 @@ use core::marker::PhantomData; -use embassy_hal_common::unborrow; +use embassy_hal_common::into_ref; use crate::gpio::sealed::AFType; use crate::gpio::{Pull, Speed}; -use crate::Unborrow; +use crate::Peripheral; mod pins; pub use pins::*; @@ -39,7 +39,7 @@ where macro_rules! config_pins { ($($pin:ident),*) => { - unborrow!($($pin),*); + into_ref!($($pin),*); $( $pin.set_as_af_pull($pin.af_num(), AFType::OutputPushPull, Pull::Up); $pin.set_speed(Speed::VeryHigh); @@ -57,12 +57,12 @@ macro_rules! fmc_sdram_constructor { ctrl: [$(($ctrl_pin_name:ident: $ctrl_signal:ident)),*] )) => { pub fn $name( - _instance: impl Unborrow + 'd, - $($addr_pin_name: impl Unborrow> + 'd),*, - $($ba_pin_name: impl Unborrow> + 'd),*, - $($d_pin_name: impl Unborrow> + 'd),*, - $($nbl_pin_name: impl Unborrow> + 'd),*, - $($ctrl_pin_name: impl Unborrow> + 'd),*, + _instance: impl Peripheral

+ 'd, + $($addr_pin_name: impl Peripheral

> + 'd),*, + $($ba_pin_name: impl Peripheral

> + 'd),*, + $($d_pin_name: impl Peripheral

> + 'd),*, + $($nbl_pin_name: impl Peripheral

> + 'd),*, + $($ctrl_pin_name: impl Peripheral

> + 'd),*, chip: CHIP ) -> stm32_fmc::Sdram, CHIP> { diff --git a/embassy-stm32/src/gpio.rs b/embassy-stm32/src/gpio.rs index 1059ebf86..3c4cdb887 100644 --- a/embassy-stm32/src/gpio.rs +++ b/embassy-stm32/src/gpio.rs @@ -1,11 +1,10 @@ #![macro_use] use core::convert::Infallible; -use core::marker::PhantomData; -use embassy_hal_common::{unborrow, unsafe_impl_unborrow}; +use embassy_hal_common::{impl_peripheral, into_ref, PeripheralRef}; use crate::pac::gpio::{self, vals}; -use crate::{pac, peripherals, Unborrow}; +use crate::{pac, peripherals, Peripheral}; /// GPIO flexible pin. /// @@ -13,8 +12,7 @@ use crate::{pac, peripherals, Unborrow}; /// set while not in output mode, so the pin's level will be 'remembered' when it is not in output /// mode. pub struct Flex<'d, T: Pin> { - pub(crate) pin: T, - phantom: PhantomData<&'d mut T>, + pub(crate) pin: PeripheralRef<'d, T>, } impl<'d, T: Pin> Flex<'d, T> { @@ -24,13 +22,10 @@ impl<'d, T: Pin> Flex<'d, T> { /// before the pin is put into output mode. /// #[inline] - pub fn new(pin: impl Unborrow + 'd) -> Self { - unborrow!(pin); + pub fn new(pin: impl Peripheral

+ 'd) -> Self { + into_ref!(pin); // Pin will be in disconnected state. - Self { - pin, - phantom: PhantomData, - } + Self { pin } } /// Put the pin into input mode. @@ -285,7 +280,7 @@ pub struct Input<'d, T: Pin> { impl<'d, T: Pin> Input<'d, T> { #[inline] - pub fn new(pin: impl Unborrow + 'd, pull: Pull) -> Self { + pub fn new(pin: impl Peripheral

+ 'd, pull: Pull) -> Self { let mut pin = Flex::new(pin); pin.set_as_input(pull); Self { pin } @@ -340,7 +335,7 @@ pub struct Output<'d, T: Pin> { impl<'d, T: Pin> Output<'d, T> { #[inline] - pub fn new(pin: impl Unborrow + 'd, initial_output: Level, speed: Speed) -> Self { + pub fn new(pin: impl Peripheral

+ 'd, initial_output: Level, speed: Speed) -> Self { let mut pin = Flex::new(pin); match initial_output { Level::High => pin.set_high(), @@ -400,7 +395,7 @@ pub struct OutputOpenDrain<'d, T: Pin> { impl<'d, T: Pin> OutputOpenDrain<'d, T> { #[inline] - pub fn new(pin: impl Unborrow + 'd, initial_output: Level, speed: Speed, pull: Pull) -> Self { + pub fn new(pin: impl Peripheral

+ 'd, initial_output: Level, speed: Speed, pull: Pull) -> Self { let mut pin = Flex::new(pin); match initial_output { @@ -626,7 +621,7 @@ pub(crate) mod sealed { } } -pub trait Pin: sealed::Pin + Sized + 'static { +pub trait Pin: Peripheral

+ Into + sealed::Pin + Sized + 'static { #[cfg(feature = "exti")] type ExtiChannel: crate::exti::Channel; @@ -673,7 +668,7 @@ impl AnyPin { } } -unsafe_impl_unborrow!(AnyPin); +impl_peripheral!(AnyPin); impl Pin for AnyPin { #[cfg(feature = "exti")] type ExtiChannel = crate::exti::AnyChannel; @@ -699,6 +694,12 @@ foreach_pin!( $port_num * 16 + $pin_num } } + + impl From for AnyPin { + fn from(x: peripherals::$pin_name) -> Self { + x.degrade() + } + } }; ); diff --git a/embassy-stm32/src/i2c/v1.rs b/embassy-stm32/src/i2c/v1.rs index 65c918780..613815a9c 100644 --- a/embassy-stm32/src/i2c/v1.rs +++ b/embassy-stm32/src/i2c/v1.rs @@ -1,13 +1,13 @@ use core::marker::PhantomData; use embassy_embedded_hal::SetConfig; -use embassy_hal_common::unborrow; +use embassy_hal_common::into_ref; use crate::gpio::sealed::AFType; use crate::i2c::{Error, Instance, SclPin, SdaPin}; use crate::pac::i2c; use crate::time::Hertz; -use crate::Unborrow; +use crate::Peripheral; pub struct State {} @@ -23,12 +23,12 @@ pub struct I2c<'d, T: Instance> { impl<'d, T: Instance> I2c<'d, T> { pub fn new( - _peri: impl Unborrow + 'd, - scl: impl Unborrow> + 'd, - sda: impl Unborrow> + 'd, + _peri: impl Peripheral

+ 'd, + scl: impl Peripheral

> + 'd, + sda: impl Peripheral

> + 'd, freq: Hertz, ) -> Self { - unborrow!(scl, sda); + into_ref!(scl, sda); T::enable(); T::reset(); diff --git a/embassy-stm32/src/i2c/v2.rs b/embassy-stm32/src/i2c/v2.rs index 108ea7e34..dec92cc88 100644 --- a/embassy-stm32/src/i2c/v2.rs +++ b/embassy-stm32/src/i2c/v2.rs @@ -1,12 +1,11 @@ use core::cmp; -use core::marker::PhantomData; use core::task::Poll; use atomic_polyfill::{AtomicUsize, Ordering}; use embassy::waitqueue::AtomicWaker; use embassy_embedded_hal::SetConfig; use embassy_hal_common::drop::OnDrop; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use futures::future::poll_fn; use crate::dma::NoDma; @@ -15,7 +14,7 @@ use crate::i2c::{Error, Instance, SclPin, SdaPin}; use crate::interrupt::InterruptExt; use crate::pac::i2c; use crate::time::Hertz; -use crate::Unborrow; +use crate::Peripheral; pub struct State { waker: AtomicWaker, @@ -32,23 +31,23 @@ impl State { } pub struct I2c<'d, T: Instance, TXDMA = NoDma, RXDMA = NoDma> { - phantom: PhantomData<&'d mut T>, - tx_dma: TXDMA, + _peri: PeripheralRef<'d, T>, + tx_dma: PeripheralRef<'d, TXDMA>, #[allow(dead_code)] - rx_dma: RXDMA, + rx_dma: PeripheralRef<'d, RXDMA>, } impl<'d, T: Instance, TXDMA, RXDMA> I2c<'d, T, TXDMA, RXDMA> { pub fn new( - _peri: impl Unborrow + 'd, - scl: impl Unborrow> + 'd, - sda: impl Unborrow> + 'd, - irq: impl Unborrow + 'd, - tx_dma: impl Unborrow + 'd, - rx_dma: impl Unborrow + 'd, + peri: impl Peripheral

+ 'd, + scl: impl Peripheral

> + 'd, + sda: impl Peripheral

> + 'd, + irq: impl Peripheral

+ 'd, + tx_dma: impl Peripheral

+ 'd, + rx_dma: impl Peripheral

+ 'd, freq: Hertz, ) -> Self { - unborrow!(irq, scl, sda, tx_dma, rx_dma); + into_ref!(peri, irq, scl, sda, tx_dma, rx_dma); T::enable(); T::reset(); @@ -88,7 +87,7 @@ impl<'d, T: Instance, TXDMA, RXDMA> I2c<'d, T, TXDMA, RXDMA> { irq.enable(); Self { - phantom: PhantomData, + _peri: peri, tx_dma, rx_dma, } diff --git a/embassy-stm32/src/lib.rs b/embassy-stm32/src/lib.rs index 8b8168589..78025f3db 100644 --- a/embassy-stm32/src/lib.rs +++ b/embassy-stm32/src/lib.rs @@ -75,7 +75,7 @@ pub(crate) mod _generated { // Reexports pub use _generated::{peripherals, Peripherals}; pub use embassy_cortex_m::executor; -pub use embassy_hal_common::{unborrow, Unborrow}; +pub use embassy_hal_common::{into_ref, Peripheral, PeripheralRef}; pub use embassy_macros::cortex_m_interrupt as interrupt; #[cfg(feature = "unstable-pac")] pub use stm32_metapac as pac; diff --git a/embassy-stm32/src/pwm/simple_pwm.rs b/embassy-stm32/src/pwm/simple_pwm.rs index 60aa110c7..7b2cdbc01 100644 --- a/embassy-stm32/src/pwm/simple_pwm.rs +++ b/embassy-stm32/src/pwm/simple_pwm.rs @@ -1,21 +1,18 @@ -use core::marker::PhantomData; - -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use super::*; #[allow(unused_imports)] use crate::gpio::sealed::{AFType, Pin}; use crate::time::Hertz; -use crate::Unborrow; +use crate::Peripheral; pub struct SimplePwm<'d, T> { - phantom: PhantomData<&'d mut T>, - inner: T, + inner: PeripheralRef<'d, T>, } macro_rules! config_pins { ($($pin:ident),*) => { - unborrow!($($pin),*); + into_ref!($($pin),*); // NOTE(unsafe) Exclusive access to the registers critical_section::with(|_| unsafe { $( @@ -30,8 +27,8 @@ macro_rules! config_pins { impl<'d, T: CaptureCompare16bitInstance> SimplePwm<'d, T> { pub fn new_1ch( - tim: impl Unborrow + 'd, - ch1: impl Unborrow> + 'd, + tim: impl Peripheral

+ 'd, + ch1: impl Peripheral

> + 'd, freq: Hertz, ) -> Self { Self::new_inner(tim, freq, move || { @@ -40,9 +37,9 @@ impl<'d, T: CaptureCompare16bitInstance> SimplePwm<'d, T> { } pub fn new_2ch( - tim: impl Unborrow + 'd, - ch1: impl Unborrow> + 'd, - ch2: impl Unborrow> + 'd, + tim: impl Peripheral

+ 'd, + ch1: impl Peripheral

> + 'd, + ch2: impl Peripheral

> + 'd, freq: Hertz, ) -> Self { Self::new_inner(tim, freq, move || { @@ -51,10 +48,10 @@ impl<'d, T: CaptureCompare16bitInstance> SimplePwm<'d, T> { } pub fn new_3ch( - tim: impl Unborrow + 'd, - ch1: impl Unborrow> + 'd, - ch2: impl Unborrow> + 'd, - ch3: impl Unborrow> + 'd, + tim: impl Peripheral

+ 'd, + ch1: impl Peripheral

> + 'd, + ch2: impl Peripheral

> + 'd, + ch3: impl Peripheral

> + 'd, freq: Hertz, ) -> Self { Self::new_inner(tim, freq, move || { @@ -63,11 +60,11 @@ impl<'d, T: CaptureCompare16bitInstance> SimplePwm<'d, T> { } pub fn new_4ch( - tim: impl Unborrow + 'd, - ch1: impl Unborrow> + 'd, - ch2: impl Unborrow> + 'd, - ch3: impl Unborrow> + 'd, - ch4: impl Unborrow> + 'd, + tim: impl Peripheral

+ 'd, + ch1: impl Peripheral

> + 'd, + ch2: impl Peripheral

> + 'd, + ch3: impl Peripheral

> + 'd, + ch4: impl Peripheral

> + 'd, freq: Hertz, ) -> Self { Self::new_inner(tim, freq, move || { @@ -75,18 +72,15 @@ impl<'d, T: CaptureCompare16bitInstance> SimplePwm<'d, T> { }) } - fn new_inner(tim: impl Unborrow + 'd, freq: Hertz, configure_pins: impl FnOnce()) -> Self { - unborrow!(tim); + fn new_inner(tim: impl Peripheral

+ 'd, freq: Hertz, configure_pins: impl FnOnce()) -> Self { + into_ref!(tim); T::enable(); ::reset(); configure_pins(); - let mut this = Self { - inner: tim, - phantom: PhantomData, - }; + let mut this = Self { inner: tim }; this.inner.set_frequency(freq); this.inner.start(); diff --git a/embassy-stm32/src/rcc/h7.rs b/embassy-stm32/src/rcc/h7.rs index 6b1014312..0185f7ae8 100644 --- a/embassy-stm32/src/rcc/h7.rs +++ b/embassy-stm32/src/rcc/h7.rs @@ -1,6 +1,6 @@ use core::marker::PhantomData; -use embassy_hal_common::unborrow; +use embassy_hal_common::into_ref; pub use pll::PllConfig; use stm32_metapac::rcc::vals::{Mco1, Mco2}; @@ -10,7 +10,7 @@ use crate::pac::rcc::vals::{Adcsel, Ckpersel, Dppre, Hpre, Hsidiv, Pllsrc, Sw, T use crate::pac::{PWR, RCC, SYSCFG}; use crate::rcc::{set_freqs, Clocks}; use crate::time::Hertz; -use crate::{peripherals, Unborrow}; +use crate::{peripherals, Peripheral}; /// HSI speed pub const HSI_FREQ: Hertz = Hertz(64_000_000); @@ -385,12 +385,12 @@ pub struct Mco<'d, T: McoInstance> { impl<'d, T: McoInstance> Mco<'d, T> { pub fn new( - _peri: impl Unborrow + 'd, - pin: impl Unborrow> + 'd, + _peri: impl Peripheral

+ 'd, + pin: impl Peripheral

> + 'd, source: impl McoSource, prescaler: McoClock, ) -> Self { - unborrow!(pin); + into_ref!(pin); critical_section::with(|_| unsafe { T::apply_clock_settings(source.into_raw(), prescaler.into_raw()); diff --git a/embassy-stm32/src/rng.rs b/embassy-stm32/src/rng.rs index 5b3558c92..2b0ee7131 100644 --- a/embassy-stm32/src/rng.rs +++ b/embassy-stm32/src/rng.rs @@ -1,14 +1,13 @@ #![macro_use] -use core::marker::PhantomData; use core::task::Poll; use embassy::waitqueue::AtomicWaker; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use futures::future::poll_fn; use rand_core::{CryptoRng, RngCore}; -use crate::{pac, peripherals, Unborrow}; +use crate::{pac, peripherals, Peripheral}; pub(crate) static RNG_WAKER: AtomicWaker = AtomicWaker::new(); @@ -19,19 +18,15 @@ pub enum Error { } pub struct Rng<'d, T: Instance> { - _inner: T, - _phantom: PhantomData<&'d mut T>, + _inner: PeripheralRef<'d, T>, } impl<'d, T: Instance> Rng<'d, T> { - pub fn new(inner: impl Unborrow + 'd) -> Self { + pub fn new(inner: impl Peripheral

+ 'd) -> Self { T::enable(); T::reset(); - unborrow!(inner); - let mut random = Self { - _inner: inner, - _phantom: PhantomData, - }; + into_ref!(inner); + let mut random = Self { _inner: inner }; random.reset(); random } diff --git a/embassy-stm32/src/sdmmc/mod.rs b/embassy-stm32/src/sdmmc/mod.rs index d94509748..b9dff8faf 100644 --- a/embassy-stm32/src/sdmmc/mod.rs +++ b/embassy-stm32/src/sdmmc/mod.rs @@ -1,23 +1,22 @@ #![macro_use] use core::default::Default; -use core::marker::PhantomData; use core::task::Poll; use embassy::waitqueue::AtomicWaker; use embassy_hal_common::drop::OnDrop; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use futures::future::poll_fn; use sdio_host::{BusWidth, CardCapacity, CardStatus, CurrentState, SDStatus, CID, CSD, OCR, SCR}; use crate::dma::NoDma; -use crate::gpio::sealed::AFType; -use crate::gpio::{Pull, Speed}; +use crate::gpio::sealed::{AFType, Pin}; +use crate::gpio::{AnyPin, Pull, Speed}; use crate::interrupt::{Interrupt, InterruptExt}; use crate::pac::sdmmc::Sdmmc as RegBlock; use crate::rcc::RccPeripheral; use crate::time::Hertz; -use crate::{peripherals, Unborrow}; +use crate::{peripherals, Peripheral}; /// The signalling scheme used on the SDMMC bus #[non_exhaustive] @@ -176,12 +175,19 @@ impl Default for Config { } /// Sdmmc device -pub struct Sdmmc<'d, T: Instance, P: Pins, Dma = NoDma> { - sdmmc: PhantomData<&'d mut T>, - pins: P, - irq: T::Interrupt, +pub struct Sdmmc<'d, T: Instance, Dma = NoDma> { + _peri: PeripheralRef<'d, T>, + irq: PeripheralRef<'d, T::Interrupt>, + dma: PeripheralRef<'d, Dma>, + + clk: PeripheralRef<'d, AnyPin>, + cmd: PeripheralRef<'d, AnyPin>, + d0: PeripheralRef<'d, AnyPin>, + d1: Option>, + d2: Option>, + d3: Option>, + config: Config, - dma: Dma, /// Current clock to card clock: Hertz, /// Current signalling scheme to card @@ -191,16 +197,99 @@ pub struct Sdmmc<'d, T: Instance, P: Pins, Dma = NoDma> { } #[cfg(sdmmc_v1)] -impl<'d, T: Instance, P: Pins, Dma: SdmmcDma> Sdmmc<'d, T, P, Dma> { - pub fn new( - _peripheral: impl Unborrow + 'd, - pins: impl Unborrow + 'd, - irq: impl Unborrow + 'd, +impl<'d, T: Instance, Dma: SdmmcDma> Sdmmc<'d, T, Dma> { + pub fn new_1bit( + sdmmc: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + dma: impl Peripheral

+ 'd, + clk: impl Peripheral

> + 'd, + cmd: impl Peripheral

> + 'd, + d0: impl Peripheral

> + 'd, config: Config, - dma: impl Unborrow + 'd, ) -> Self { - unborrow!(irq, pins, dma); - pins.configure(); + into_ref!(clk, cmd, d0); + + critical_section::with(|_| unsafe { + clk.set_as_af_pull(clk.af_num(), AFType::OutputPushPull, Pull::None); + cmd.set_as_af_pull(cmd.af_num(), AFType::OutputPushPull, Pull::Up); + d0.set_as_af_pull(d0.af_num(), AFType::OutputPushPull, Pull::Up); + + clk.set_speed(Speed::VeryHigh); + cmd.set_speed(Speed::VeryHigh); + d0.set_speed(Speed::VeryHigh); + }); + + Self::new_inner( + sdmmc, + irq, + dma, + clk.map_into(), + cmd.map_into(), + d0.map_into(), + None, + None, + None, + config, + ) + } + + pub fn new_4bit( + sdmmc: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + dma: impl Peripheral

+ 'd, + clk: impl Peripheral

> + 'd, + cmd: impl Peripheral

> + 'd, + d0: impl Peripheral

> + 'd, + d1: impl Peripheral

> + 'd, + d2: impl Peripheral

> + 'd, + d3: impl Peripheral

> + 'd, + config: Config, + ) -> Self { + into_ref!(clk, cmd, d0, d1, d2, d3); + + critical_section::with(|_| unsafe { + clk.set_as_af_pull(clk.af_num(), AFType::OutputPushPull, Pull::None); + cmd.set_as_af_pull(cmd.af_num(), AFType::OutputPushPull, Pull::Up); + d0.set_as_af_pull(d0.af_num(), AFType::OutputPushPull, Pull::Up); + d1.set_as_af_pull(d1.af_num(), AFType::OutputPushPull, Pull::Up); + d2.set_as_af_pull(d2.af_num(), AFType::OutputPushPull, Pull::Up); + d3.set_as_af_pull(d3.af_num(), AFType::OutputPushPull, Pull::Up); + + clk.set_speed(Speed::VeryHigh); + cmd.set_speed(Speed::VeryHigh); + d0.set_speed(Speed::VeryHigh); + d1.set_speed(Speed::VeryHigh); + d2.set_speed(Speed::VeryHigh); + d3.set_speed(Speed::VeryHigh); + }); + + Self::new_inner( + sdmmc, + irq, + dma, + clk.map_into(), + cmd.map_into(), + d0.map_into(), + Some(d1.map_into()), + Some(d2.map_into()), + Some(d3.map_into()), + config, + ) + } + + fn new_inner( + sdmmc: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + dma: impl Peripheral

+ 'd, + clk: PeripheralRef<'d, AnyPin>, + cmd: PeripheralRef<'d, AnyPin>, + d0: PeripheralRef<'d, AnyPin>, + d1: Option>, + d2: Option>, + d3: Option>, + config: Config, + ) -> Self { + into_ref!(sdmmc, irq, dma); T::enable(); T::reset(); @@ -213,11 +302,18 @@ impl<'d, T: Instance, P: Pins, Dma: SdmmcDma> Sdmmc<'d, T, P, Dma> { irq.enable(); Self { - sdmmc: PhantomData, - pins, + _peri: sdmmc, irq, - config, dma, + + clk, + cmd, + d0, + d1, + d2, + d3, + + config, clock, signalling: Default::default(), card: None, @@ -226,15 +322,94 @@ impl<'d, T: Instance, P: Pins, Dma: SdmmcDma> Sdmmc<'d, T, P, Dma> { } #[cfg(sdmmc_v2)] -impl<'d, T: Instance, P: Pins> Sdmmc<'d, T, P, NoDma> { - pub fn new( - _peripheral: impl Unborrow + 'd, - pins: impl Unborrow + 'd, - irq: impl Unborrow + 'd, +impl<'d, T: Instance> Sdmmc<'d, T, NoDma> { + pub fn new_1bit( + sdmmc: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + clk: impl Peripheral

> + 'd, + cmd: impl Peripheral

> + 'd, + d0: impl Peripheral

> + 'd, config: Config, ) -> Self { - unborrow!(irq, pins); - pins.configure(); + into_ref!(clk, cmd, d0); + + critical_section::with(|_| unsafe { + clk.set_as_af_pull(clk.af_num(), AFType::OutputPushPull, Pull::None); + cmd.set_as_af_pull(cmd.af_num(), AFType::OutputPushPull, Pull::Up); + d0.set_as_af_pull(d0.af_num(), AFType::OutputPushPull, Pull::Up); + + clk.set_speed(Speed::VeryHigh); + cmd.set_speed(Speed::VeryHigh); + d0.set_speed(Speed::VeryHigh); + }); + + Self::new_inner( + sdmmc, + irq, + clk.map_into(), + cmd.map_into(), + d0.map_into(), + None, + None, + None, + config, + ) + } + + pub fn new_4bit( + sdmmc: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + clk: impl Peripheral

> + 'd, + cmd: impl Peripheral

> + 'd, + d0: impl Peripheral

> + 'd, + d1: impl Peripheral

> + 'd, + d2: impl Peripheral

> + 'd, + d3: impl Peripheral

> + 'd, + config: Config, + ) -> Self { + into_ref!(clk, cmd, d0, d1, d2, d3); + + critical_section::with(|_| unsafe { + clk.set_as_af_pull(clk.af_num(), AFType::OutputPushPull, Pull::None); + cmd.set_as_af_pull(cmd.af_num(), AFType::OutputPushPull, Pull::Up); + d0.set_as_af_pull(d0.af_num(), AFType::OutputPushPull, Pull::Up); + d1.set_as_af_pull(d1.af_num(), AFType::OutputPushPull, Pull::Up); + d2.set_as_af_pull(d2.af_num(), AFType::OutputPushPull, Pull::Up); + d3.set_as_af_pull(d3.af_num(), AFType::OutputPushPull, Pull::Up); + + clk.set_speed(Speed::VeryHigh); + cmd.set_speed(Speed::VeryHigh); + d0.set_speed(Speed::VeryHigh); + d1.set_speed(Speed::VeryHigh); + d2.set_speed(Speed::VeryHigh); + d3.set_speed(Speed::VeryHigh); + }); + + Self::new_inner( + sdmmc, + irq, + clk.map_into(), + cmd.map_into(), + d0.map_into(), + Some(d1.map_into()), + Some(d2.map_into()), + Some(d3.map_into()), + config, + ) + } + + fn new_inner( + sdmmc: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + clk: PeripheralRef<'d, AnyPin>, + cmd: PeripheralRef<'d, AnyPin>, + d0: PeripheralRef<'d, AnyPin>, + d1: Option>, + d2: Option>, + d3: Option>, + config: Config, + ) -> Self { + into_ref!(sdmmc, irq); T::enable(); T::reset(); @@ -247,11 +422,18 @@ impl<'d, T: Instance, P: Pins> Sdmmc<'d, T, P, NoDma> { irq.enable(); Self { - sdmmc: PhantomData, - pins, + _peri: sdmmc, irq, + dma: NoDma.into_ref(), + + clk, + cmd, + d0, + d1, + d2, + d3, + config, - dma: NoDma, clock, signalling: Default::default(), card: None, @@ -259,23 +441,28 @@ impl<'d, T: Instance, P: Pins> Sdmmc<'d, T, P, NoDma> { } } -impl<'d, T: Instance, P: Pins, Dma: SdmmcDma> Sdmmc<'d, T, P, Dma> { +impl<'d, T: Instance, Dma: SdmmcDma> Sdmmc<'d, T, Dma> { #[inline(always)] pub async fn init_card(&mut self, freq: Hertz) -> Result<(), Error> { let inner = T::inner(); let freq = freq.into(); + let bus_width = match self.d3.is_some() { + true => BusWidth::Four, + false => BusWidth::One, + }; + inner .init_card( freq, - P::BUSWIDTH, + bus_width, &mut self.card, &mut self.signalling, T::frequency(), &mut self.clock, T::state(), self.config.data_transfer_timeout, - &mut self.dma, + &mut *self.dma, ) .await } @@ -295,7 +482,7 @@ impl<'d, T: Instance, P: Pins, Dma: SdmmcDma> Sdmmc<'d, T, P, Dma> { card_capacity, state, self.config.data_transfer_timeout, - &mut self.dma, + &mut *self.dma, ) .await } @@ -314,7 +501,7 @@ impl<'d, T: Instance, P: Pins, Dma: SdmmcDma> Sdmmc<'d, T, P, Dma> { card, state, self.config.data_transfer_timeout, - &mut self.dma, + &mut *self.dma, ) .await } @@ -345,12 +532,26 @@ impl<'d, T: Instance, P: Pins, Dma: SdmmcDma> Sdmmc<'d, T, P, Dma> { } } -impl<'d, T: Instance, P: Pins, Dma> Drop for Sdmmc<'d, T, P, Dma> { +impl<'d, T: Instance, Dma> Drop for Sdmmc<'d, T, Dma> { fn drop(&mut self) { self.irq.disable(); let inner = T::inner(); unsafe { inner.on_drop() }; - self.pins.deconfigure(); + + critical_section::with(|_| unsafe { + self.clk.set_as_disconnected(); + self.cmd.set_as_disconnected(); + self.d0.set_as_disconnected(); + if let Some(x) = &mut self.d1 { + x.set_as_disconnected(); + } + if let Some(x) = &mut self.d2 { + x.set_as_disconnected(); + } + if let Some(x) = &mut self.d3 { + x.set_as_disconnected(); + } + }); } } @@ -1296,114 +1497,6 @@ cfg_if::cfg_if! { } } -pub trait Pins: sealed::Pins + 'static { - const BUSWIDTH: BusWidth; - - fn configure(&mut self); - fn deconfigure(&mut self); -} - -impl sealed::Pins for (CLK, CMD, D0, D1, D2, D3) -where - T: Instance, - CLK: CkPin, - CMD: CmdPin, - D0: D0Pin, - D1: D1Pin, - D2: D2Pin, - D3: D3Pin, -{ -} - -impl sealed::Pins for (CLK, CMD, D0) -where - T: Instance, - CLK: CkPin, - CMD: CmdPin, - D0: D0Pin, -{ -} - -impl Pins for (CLK, CMD, D0, D1, D2, D3) -where - T: Instance, - CLK: CkPin, - CMD: CmdPin, - D0: D0Pin, - D1: D1Pin, - D2: D2Pin, - D3: D3Pin, -{ - const BUSWIDTH: BusWidth = BusWidth::Four; - - fn configure(&mut self) { - let (clk_pin, cmd_pin, d0_pin, d1_pin, d2_pin, d3_pin) = self; - - critical_section::with(|_| unsafe { - clk_pin.set_as_af_pull(clk_pin.af_num(), AFType::OutputPushPull, Pull::None); - cmd_pin.set_as_af_pull(cmd_pin.af_num(), AFType::OutputPushPull, Pull::Up); - d0_pin.set_as_af_pull(d0_pin.af_num(), AFType::OutputPushPull, Pull::Up); - d1_pin.set_as_af_pull(d1_pin.af_num(), AFType::OutputPushPull, Pull::Up); - d2_pin.set_as_af_pull(d2_pin.af_num(), AFType::OutputPushPull, Pull::Up); - d3_pin.set_as_af_pull(d3_pin.af_num(), AFType::OutputPushPull, Pull::Up); - - clk_pin.set_speed(Speed::VeryHigh); - cmd_pin.set_speed(Speed::VeryHigh); - d0_pin.set_speed(Speed::VeryHigh); - d1_pin.set_speed(Speed::VeryHigh); - d2_pin.set_speed(Speed::VeryHigh); - d3_pin.set_speed(Speed::VeryHigh); - }); - } - - fn deconfigure(&mut self) { - let (clk_pin, cmd_pin, d0_pin, d1_pin, d2_pin, d3_pin) = self; - - critical_section::with(|_| unsafe { - clk_pin.set_as_disconnected(); - cmd_pin.set_as_disconnected(); - d0_pin.set_as_disconnected(); - d1_pin.set_as_disconnected(); - d2_pin.set_as_disconnected(); - d3_pin.set_as_disconnected(); - }); - } -} - -impl Pins for (CLK, CMD, D0) -where - T: Instance, - CLK: CkPin, - CMD: CmdPin, - D0: D0Pin, -{ - const BUSWIDTH: BusWidth = BusWidth::One; - - fn configure(&mut self) { - let (clk_pin, cmd_pin, d0_pin) = self; - - critical_section::with(|_| unsafe { - clk_pin.set_as_af_pull(clk_pin.af_num(), AFType::OutputPushPull, Pull::None); - cmd_pin.set_as_af_pull(cmd_pin.af_num(), AFType::OutputPushPull, Pull::Up); - d0_pin.set_as_af_pull(d0_pin.af_num(), AFType::OutputPushPull, Pull::Up); - - clk_pin.set_speed(Speed::VeryHigh); - cmd_pin.set_speed(Speed::VeryHigh); - d0_pin.set_speed(Speed::VeryHigh); - }); - } - - fn deconfigure(&mut self) { - let (clk_pin, cmd_pin, d0_pin) = self; - - critical_section::with(|_| unsafe { - clk_pin.set_as_disconnected(); - cmd_pin.set_as_disconnected(); - d0_pin.set_as_disconnected(); - }); - } -} - foreach_peripheral!( (sdmmc, $inst:ident) => { impl sealed::Instance for peripherals::$inst { diff --git a/embassy-stm32/src/spi/mod.rs b/embassy-stm32/src/spi/mod.rs index a02f4492f..26fb392ef 100644 --- a/embassy-stm32/src/spi/mod.rs +++ b/embassy-stm32/src/spi/mod.rs @@ -1,10 +1,9 @@ #![macro_use] -use core::marker::PhantomData; use core::ptr; use embassy_embedded_hal::SetConfig; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; pub use embedded_hal_02::spi::{Mode, Phase, Polarity, MODE_0, MODE_1, MODE_2, MODE_3}; use futures::future::join; @@ -15,7 +14,7 @@ use crate::gpio::AnyPin; use crate::pac::spi::{regs, vals, Spi as Regs}; use crate::rcc::RccPeripheral; use crate::time::Hertz; -use crate::{peripherals, Unborrow}; +use crate::{peripherals, Peripheral}; #[derive(Debug)] #[cfg_attr(feature = "defmt", derive(defmt::Format))] @@ -73,27 +72,27 @@ impl Config { } pub struct Spi<'d, T: Instance, Tx, Rx> { - sck: Option, - mosi: Option, - miso: Option, - txdma: Tx, - rxdma: Rx, + _peri: PeripheralRef<'d, T>, + sck: Option>, + mosi: Option>, + miso: Option>, + txdma: PeripheralRef<'d, Tx>, + rxdma: PeripheralRef<'d, Rx>, current_word_size: WordSize, - phantom: PhantomData<&'d mut T>, } impl<'d, T: Instance, Tx, Rx> Spi<'d, T, Tx, Rx> { pub fn new( - peri: impl Unborrow + 'd, - sck: impl Unborrow> + 'd, - mosi: impl Unborrow> + 'd, - miso: impl Unborrow> + 'd, - txdma: impl Unborrow + 'd, - rxdma: impl Unborrow + 'd, + peri: impl Peripheral

+ 'd, + sck: impl Peripheral

> + 'd, + mosi: impl Peripheral

> + 'd, + miso: impl Peripheral

> + 'd, + txdma: impl Peripheral

+ 'd, + rxdma: impl Peripheral

+ 'd, freq: Hertz, config: Config, ) -> Self { - unborrow!(sck, mosi, miso); + into_ref!(peri, sck, mosi, miso); unsafe { sck.set_as_af(sck.af_num(), AFType::OutputPushPull); #[cfg(any(spi_v2, spi_v3, spi_v4))] @@ -108,9 +107,9 @@ impl<'d, T: Instance, Tx, Rx> Spi<'d, T, Tx, Rx> { Self::new_inner( peri, - Some(sck.degrade()), - Some(mosi.degrade()), - Some(miso.degrade()), + Some(sck.map_into()), + Some(mosi.map_into()), + Some(miso.map_into()), txdma, rxdma, freq, @@ -119,15 +118,15 @@ impl<'d, T: Instance, Tx, Rx> Spi<'d, T, Tx, Rx> { } pub fn new_rxonly( - peri: impl Unborrow + 'd, - sck: impl Unborrow> + 'd, - miso: impl Unborrow> + 'd, - txdma: impl Unborrow + 'd, // TODO remove - rxdma: impl Unborrow + 'd, + peri: impl Peripheral

+ 'd, + sck: impl Peripheral

> + 'd, + miso: impl Peripheral

> + 'd, + txdma: impl Peripheral

+ 'd, // TODO remove + rxdma: impl Peripheral

+ 'd, freq: Hertz, config: Config, ) -> Self { - unborrow!(sck, miso); + into_ref!(sck, miso); unsafe { sck.set_as_af(sck.af_num(), AFType::OutputPushPull); #[cfg(any(spi_v2, spi_v3, spi_v4))] @@ -139,9 +138,9 @@ impl<'d, T: Instance, Tx, Rx> Spi<'d, T, Tx, Rx> { Self::new_inner( peri, - Some(sck.degrade()), + Some(sck.map_into()), None, - Some(miso.degrade()), + Some(miso.map_into()), txdma, rxdma, freq, @@ -150,15 +149,15 @@ impl<'d, T: Instance, Tx, Rx> Spi<'d, T, Tx, Rx> { } pub fn new_txonly( - peri: impl Unborrow + 'd, - sck: impl Unborrow> + 'd, - mosi: impl Unborrow> + 'd, - txdma: impl Unborrow + 'd, - rxdma: impl Unborrow + 'd, // TODO remove + peri: impl Peripheral

+ 'd, + sck: impl Peripheral

> + 'd, + mosi: impl Peripheral

> + 'd, + txdma: impl Peripheral

+ 'd, + rxdma: impl Peripheral

+ 'd, // TODO remove freq: Hertz, config: Config, ) -> Self { - unborrow!(sck, mosi); + into_ref!(sck, mosi); unsafe { sck.set_as_af(sck.af_num(), AFType::OutputPushPull); #[cfg(any(spi_v2, spi_v3, spi_v4))] @@ -170,8 +169,8 @@ impl<'d, T: Instance, Tx, Rx> Spi<'d, T, Tx, Rx> { Self::new_inner( peri, - Some(sck.degrade()), - Some(mosi.degrade()), + Some(sck.map_into()), + Some(mosi.map_into()), None, txdma, rxdma, @@ -181,16 +180,16 @@ impl<'d, T: Instance, Tx, Rx> Spi<'d, T, Tx, Rx> { } fn new_inner( - _peri: impl Unborrow + 'd, - sck: Option, - mosi: Option, - miso: Option, - txdma: impl Unborrow + 'd, - rxdma: impl Unborrow + 'd, + peri: impl Peripheral

+ 'd, + sck: Option>, + mosi: Option>, + miso: Option>, + txdma: impl Peripheral

+ 'd, + rxdma: impl Peripheral

+ 'd, freq: Hertz, config: Config, ) -> Self { - unborrow!(txdma, rxdma); + into_ref!(peri, txdma, rxdma); let pclk = T::frequency(); let br = compute_baud_rate(pclk, freq.into()); @@ -280,13 +279,13 @@ impl<'d, T: Instance, Tx, Rx> Spi<'d, T, Tx, Rx> { } Self { + _peri: peri, sck, mosi, miso, txdma, rxdma, current_word_size: WordSize::EightBit, - phantom: PhantomData, } } @@ -995,7 +994,7 @@ pub trait Word: Copy + 'static + sealed::Word + Default + crate::dma::Word {} impl Word for u8 {} impl Word for u16 {} -pub trait Instance: sealed::Instance + RccPeripheral {} +pub trait Instance: Peripheral

+ sealed::Instance + RccPeripheral {} pin_trait!(SckPin, Instance); pin_trait!(MosiPin, Instance); pin_trait!(MisoPin, Instance); diff --git a/embassy-stm32/src/subghz/mod.rs b/embassy-stm32/src/subghz/mod.rs index ce513ec63..f02fc140f 100644 --- a/embassy-stm32/src/subghz/mod.rs +++ b/embassy-stm32/src/subghz/mod.rs @@ -83,7 +83,7 @@ use crate::peripherals::SUBGHZSPI; use crate::rcc::sealed::RccPeripheral; use crate::spi::{BitOrder, Config as SpiConfig, MisoPin, MosiPin, SckPin, Spi, MODE_0}; use crate::time::Hertz; -use crate::{pac, Unborrow}; +use crate::{pac, Peripheral}; /// Passthrough for SPI errors (for now) pub type Error = crate::spi::Error; @@ -211,12 +211,12 @@ impl<'d, Tx, Rx> SubGhz<'d, Tx, Rx> { /// This will reset the radio and the SPI bus, and enable the peripheral /// clock. pub fn new( - peri: impl Unborrow + 'd, - sck: impl Unborrow> + 'd, - mosi: impl Unborrow> + 'd, - miso: impl Unborrow> + 'd, - txdma: impl Unborrow + 'd, - rxdma: impl Unborrow + 'd, + peri: impl Peripheral

+ 'd, + sck: impl Peripheral

> + 'd, + mosi: impl Peripheral

> + 'd, + miso: impl Peripheral

> + 'd, + txdma: impl Peripheral

+ 'd, + rxdma: impl Peripheral

+ 'd, ) -> Self { Self::pulse_radio_reset(); diff --git a/embassy-stm32/src/usart/buffered.rs b/embassy-stm32/src/usart/buffered.rs index c4703cff2..4e47ef73d 100644 --- a/embassy-stm32/src/usart/buffered.rs +++ b/embassy-stm32/src/usart/buffered.rs @@ -39,11 +39,11 @@ impl<'d, T: Instance> BufferedUart<'d, T> { pub fn new( state: &'d mut State<'d, T>, _uart: Uart<'d, T, NoDma, NoDma>, - irq: impl Unborrow + 'd, + irq: impl Peripheral

+ 'd, tx_buffer: &'d mut [u8], rx_buffer: &'d mut [u8], ) -> BufferedUart<'d, T> { - unborrow!(irq); + into_ref!(irq); let r = T::regs(); unsafe { diff --git a/embassy-stm32/src/usart/mod.rs b/embassy-stm32/src/usart/mod.rs index a893e4b80..ca75bab41 100644 --- a/embassy-stm32/src/usart/mod.rs +++ b/embassy-stm32/src/usart/mod.rs @@ -2,14 +2,14 @@ use core::marker::PhantomData; -use embassy_hal_common::unborrow; +use embassy_hal_common::{into_ref, PeripheralRef}; use crate::dma::NoDma; use crate::gpio::sealed::AFType; use crate::interrupt::Interrupt; use crate::pac::usart::{regs, vals}; use crate::rcc::RccPeripheral; -use crate::{peripherals, Unborrow}; +use crate::{peripherals, Peripheral}; #[derive(Clone, Copy, PartialEq, Eq, Debug)] pub enum DataBits { @@ -72,23 +72,22 @@ pub enum Error { } pub struct Uart<'d, T: Instance, TxDma = NoDma, RxDma = NoDma> { - phantom: PhantomData<&'d mut T>, tx: UartTx<'d, T, TxDma>, rx: UartRx<'d, T, RxDma>, } pub struct UartTx<'d, T: Instance, TxDma = NoDma> { phantom: PhantomData<&'d mut T>, - tx_dma: TxDma, + tx_dma: PeripheralRef<'d, TxDma>, } pub struct UartRx<'d, T: Instance, RxDma = NoDma> { phantom: PhantomData<&'d mut T>, - rx_dma: RxDma, + rx_dma: PeripheralRef<'d, RxDma>, } impl<'d, T: Instance, TxDma> UartTx<'d, T, TxDma> { - fn new(tx_dma: TxDma) -> Self { + fn new(tx_dma: PeripheralRef<'d, TxDma>) -> Self { Self { tx_dma, phantom: PhantomData, @@ -134,7 +133,7 @@ impl<'d, T: Instance, TxDma> UartTx<'d, T, TxDma> { } impl<'d, T: Instance, RxDma> UartRx<'d, T, RxDma> { - fn new(rx_dma: RxDma) -> Self { + fn new(rx_dma: PeripheralRef<'d, RxDma>) -> Self { Self { rx_dma, phantom: PhantomData, @@ -190,14 +189,14 @@ impl<'d, T: Instance, RxDma> UartRx<'d, T, RxDma> { impl<'d, T: Instance, TxDma, RxDma> Uart<'d, T, TxDma, RxDma> { pub fn new( - _inner: impl Unborrow + 'd, - rx: impl Unborrow> + 'd, - tx: impl Unborrow> + 'd, - tx_dma: impl Unborrow + 'd, - rx_dma: impl Unborrow + 'd, + _inner: impl Peripheral

+ 'd, + rx: impl Peripheral

> + 'd, + tx: impl Peripheral

> + 'd, + tx_dma: impl Peripheral

+ 'd, + rx_dma: impl Peripheral

+ 'd, config: Config, ) -> Self { - unborrow!(_inner, rx, tx, tx_dma, rx_dma); + into_ref!(_inner, rx, tx, tx_dma, rx_dma); T::enable(); T::reset(); @@ -234,7 +233,6 @@ impl<'d, T: Instance, TxDma, RxDma> Uart<'d, T, TxDma, RxDma> { } Self { - phantom: PhantomData, tx: UartTx::new(tx_dma), rx: UartRx::new(rx_dma), } diff --git a/embassy-stm32/src/usb/usb.rs b/embassy-stm32/src/usb/usb.rs index 4633ff00c..11ef75954 100644 --- a/embassy-stm32/src/usb/usb.rs +++ b/embassy-stm32/src/usb/usb.rs @@ -7,7 +7,7 @@ use core::task::Poll; use atomic_polyfill::{AtomicBool, AtomicU8}; use embassy::time::{block_for, Duration}; use embassy::waitqueue::AtomicWaker; -use embassy_hal_common::unborrow; +use embassy_hal_common::into_ref; use embassy_usb::driver::{self, EndpointAllocError, EndpointError, Event, Unsupported}; use embassy_usb::types::{EndpointAddress, EndpointInfo, EndpointType, UsbDirection}; use futures::future::poll_fn; @@ -20,7 +20,7 @@ use crate::gpio::sealed::AFType; use crate::interrupt::InterruptExt; use crate::pac::usb::regs; use crate::rcc::sealed::RccPeripheral; -use crate::{pac, Unborrow}; +use crate::{pac, Peripheral}; const EP_COUNT: usize = 8; @@ -125,12 +125,12 @@ pub struct Driver<'d, T: Instance> { impl<'d, T: Instance> Driver<'d, T> { pub fn new( - _usb: impl Unborrow + 'd, - irq: impl Unborrow + 'd, - dp: impl Unborrow> + 'd, - dm: impl Unborrow> + 'd, + _usb: impl Peripheral

+ 'd, + irq: impl Peripheral

+ 'd, + dp: impl Peripheral

> + 'd, + dm: impl Peripheral

> + 'd, ) -> Self { - unborrow!(irq, dp, dm); + into_ref!(irq, dp, dm); irq.set_handler(Self::on_interrupt); irq.unpend(); irq.enable(); diff --git a/embassy-stm32/src/usb_otg.rs b/embassy-stm32/src/usb_otg.rs index 581754135..f7faf12a8 100644 --- a/embassy-stm32/src/usb_otg.rs +++ b/embassy-stm32/src/usb_otg.rs @@ -1,14 +1,14 @@ use core::marker::PhantomData; -use embassy_hal_common::unborrow; +use embassy_hal_common::into_ref; use crate::gpio::sealed::AFType; use crate::rcc::RccPeripheral; -use crate::{peripherals, Unborrow}; +use crate::{peripherals, Peripheral}; macro_rules! config_ulpi_pins { ($($pin:ident),*) => { - unborrow!($($pin),*); + into_ref!($($pin),*); // NOTE(unsafe) Exclusive access to the registers critical_section::with(|_| unsafe { $( @@ -43,11 +43,11 @@ pub struct UsbOtg<'d, T: Instance> { impl<'d, T: Instance> UsbOtg<'d, T> { /// Initializes USB OTG peripheral with internal Full-Speed PHY pub fn new_fs( - _peri: impl Unborrow + 'd, - dp: impl Unborrow> + 'd, - dm: impl Unborrow> + 'd, + _peri: impl Peripheral

+ 'd, + dp: impl Peripheral

> + 'd, + dm: impl Peripheral

> + 'd, ) -> Self { - unborrow!(dp, dm); + into_ref!(dp, dm); unsafe { dp.set_as_af(dp.af_num(), AFType::OutputPushPull); @@ -62,19 +62,19 @@ impl<'d, T: Instance> UsbOtg<'d, T> { /// Initializes USB OTG peripheral with external High-Speed PHY pub fn new_hs_ulpi( - _peri: impl Unborrow + 'd, - ulpi_clk: impl Unborrow> + 'd, - ulpi_dir: impl Unborrow> + 'd, - ulpi_nxt: impl Unborrow> + 'd, - ulpi_stp: impl Unborrow> + 'd, - ulpi_d0: impl Unborrow> + 'd, - ulpi_d1: impl Unborrow> + 'd, - ulpi_d2: impl Unborrow> + 'd, - ulpi_d3: impl Unborrow> + 'd, - ulpi_d4: impl Unborrow> + 'd, - ulpi_d5: impl Unborrow> + 'd, - ulpi_d6: impl Unborrow> + 'd, - ulpi_d7: impl Unborrow> + 'd, + _peri: impl Peripheral

+ 'd, + ulpi_clk: impl Peripheral

> + 'd, + ulpi_dir: impl Peripheral

> + 'd, + ulpi_nxt: impl Peripheral

> + 'd, + ulpi_stp: impl Peripheral

> + 'd, + ulpi_d0: impl Peripheral

> + 'd, + ulpi_d1: impl Peripheral

> + 'd, + ulpi_d2: impl Peripheral

> + 'd, + ulpi_d3: impl Peripheral

> + 'd, + ulpi_d4: impl Peripheral

> + 'd, + ulpi_d5: impl Peripheral

> + 'd, + ulpi_d6: impl Peripheral

> + 'd, + ulpi_d7: impl Peripheral

> + 'd, ) -> Self { config_ulpi_pins!( ulpi_clk, ulpi_dir, ulpi_nxt, ulpi_stp, ulpi_d0, ulpi_d1, ulpi_d2, ulpi_d3, ulpi_d4, ulpi_d5, ulpi_d6, diff --git a/embassy-stm32/src/wdg/mod.rs b/embassy-stm32/src/wdg/mod.rs index c4b2609b1..85176eefc 100644 --- a/embassy-stm32/src/wdg/mod.rs +++ b/embassy-stm32/src/wdg/mod.rs @@ -1,6 +1,6 @@ use core::marker::PhantomData; -use embassy_hal_common::{unborrow, Unborrow}; +use embassy_hal_common::{into_ref, Peripheral}; use stm32_metapac::iwdg::vals::{Key, Pr}; use crate::rcc::LSI_FREQ; @@ -27,8 +27,8 @@ impl<'d, T: Instance> IndependentWatchdog<'d, T> { /// /// [Self] has to be started with [Self::unleash()]. /// Once timer expires, MCU will be reset. To prevent this, timer must be reloaded by repeatedly calling [Self::pet()] within timeout interval. - pub fn new(_instance: impl Unborrow + 'd, timeout_us: u32) -> Self { - unborrow!(_instance); + pub fn new(_instance: impl Peripheral

+ 'd, timeout_us: u32) -> Self { + into_ref!(_instance); // Find lowest prescaler value, which makes watchdog period longer or equal to timeout. // This iterates from 4 (2^2) to 256 (2^8). diff --git a/examples/stm32f4/src/bin/sdmmc.rs b/examples/stm32f4/src/bin/sdmmc.rs index 665670261..752ad57bf 100644 --- a/examples/stm32f4/src/bin/sdmmc.rs +++ b/examples/stm32f4/src/bin/sdmmc.rs @@ -21,12 +21,17 @@ async fn main(_spawner: Spawner, p: Peripherals) -> ! { let irq = interrupt::take!(SDIO); - let mut sdmmc = Sdmmc::new( + let mut sdmmc = Sdmmc::new_4bit( p.SDIO, - (p.PC12, p.PD2, p.PC8, p.PC9, p.PC10, p.PC11), irq, - Default::default(), p.DMA2_CH3, + p.PC12, + p.PD2, + p.PC8, + p.PC9, + p.PC10, + p.PC11, + Default::default(), ); // Should print 400kHz for initialization diff --git a/examples/stm32f7/src/bin/sdmmc.rs b/examples/stm32f7/src/bin/sdmmc.rs index 011e1fd95..be1c2b152 100644 --- a/examples/stm32f7/src/bin/sdmmc.rs +++ b/examples/stm32f7/src/bin/sdmmc.rs @@ -21,12 +21,17 @@ async fn main(_spawner: Spawner, p: Peripherals) -> ! { let irq = interrupt::take!(SDMMC1); - let mut sdmmc = Sdmmc::new( + let mut sdmmc = Sdmmc::new_4bit( p.SDMMC1, - (p.PC12, p.PD2, p.PC8, p.PC9, p.PC10, p.PC11), irq, - Default::default(), p.DMA2_CH3, + p.PC12, + p.PD2, + p.PC8, + p.PC9, + p.PC10, + p.PC11, + Default::default(), ); // Should print 400kHz for initialization diff --git a/examples/stm32h7/src/bin/low_level_timer_api.rs b/examples/stm32h7/src/bin/low_level_timer_api.rs index fc19d84e4..d7c6da5bd 100644 --- a/examples/stm32h7/src/bin/low_level_timer_api.rs +++ b/examples/stm32h7/src/bin/low_level_timer_api.rs @@ -2,8 +2,6 @@ #![no_main] #![feature(type_alias_impl_trait)] -use core::marker::PhantomData; - use defmt::*; use embassy::executor::Spawner; use embassy::time::{Duration, Timer}; @@ -11,7 +9,7 @@ use embassy_stm32::gpio::low_level::AFType; use embassy_stm32::gpio::Speed; use embassy_stm32::pwm::*; use embassy_stm32::time::{khz, mhz, Hertz}; -use embassy_stm32::{unborrow, Config, Peripherals, Unborrow}; +use embassy_stm32::{into_ref, Config, Peripheral, PeripheralRef, Peripherals}; use {defmt_rtt as _, panic_probe as _}; pub fn config() -> Config { @@ -49,20 +47,19 @@ async fn main(_spawner: Spawner, p: Peripherals) { } } pub struct SimplePwm32<'d, T: CaptureCompare32bitInstance> { - phantom: PhantomData<&'d mut T>, - inner: T, + inner: PeripheralRef<'d, T>, } impl<'d, T: CaptureCompare32bitInstance> SimplePwm32<'d, T> { pub fn new( - tim: impl Unborrow + 'd, - ch1: impl Unborrow> + 'd, - ch2: impl Unborrow> + 'd, - ch3: impl Unborrow> + 'd, - ch4: impl Unborrow> + 'd, + tim: impl Peripheral

+ 'd, + ch1: impl Peripheral

> + 'd, + ch2: impl Peripheral

> + 'd, + ch3: impl Peripheral

> + 'd, + ch4: impl Peripheral

> + 'd, freq: Hertz, ) -> Self { - unborrow!(tim, ch1, ch2, ch3, ch4); + into_ref!(tim, ch1, ch2, ch3, ch4); T::enable(); ::reset(); @@ -78,10 +75,7 @@ impl<'d, T: CaptureCompare32bitInstance> SimplePwm32<'d, T> { ch4.set_as_af(ch1.af_num(), AFType::OutputPushPull); } - let mut this = Self { - inner: tim, - phantom: PhantomData, - }; + let mut this = Self { inner: tim }; this.set_freq(freq); this.inner.start(); diff --git a/examples/stm32h7/src/bin/sdmmc.rs b/examples/stm32h7/src/bin/sdmmc.rs index 787f700ae..163807d86 100644 --- a/examples/stm32h7/src/bin/sdmmc.rs +++ b/examples/stm32h7/src/bin/sdmmc.rs @@ -21,10 +21,15 @@ async fn main(_spawner: Spawner, p: Peripherals) -> ! { let irq = interrupt::take!(SDMMC1); - let mut sdmmc = Sdmmc::new( + let mut sdmmc = Sdmmc::new_4bit( p.SDMMC1, - (p.PC12, p.PD2, p.PC8, p.PC9, p.PC10, p.PC11), irq, + p.PC12, + p.PD2, + p.PC8, + p.PC9, + p.PC10, + p.PC11, Default::default(), );