Merge upstream

This commit is contained in:
Mehmet Ali Anil
2023-03-07 10:46:59 +01:00
105 changed files with 3066 additions and 1594 deletions

File diff suppressed because it is too large Load Diff

View File

@ -140,6 +140,10 @@ impl_twim!(TWI0, TWIM0, TWIM0_TWIS0_TWI0);
impl_twis!(TWI0, TWIS0, TWIM0_TWIS0_TWI0);
impl_qdec!(QDEC, QDEC, QDEC);
impl_rng!(RNG, RNG, RNG);
impl_timer!(TIMER0, TIMER0, TIMER0);
impl_timer!(TIMER1, TIMER1, TIMER1);
impl_timer!(TIMER2, TIMER2, TIMER2);

View File

@ -148,6 +148,12 @@ impl_twis!(TWI0, TWIS0, TWIM0_TWIS0_TWI0);
impl_pwm!(PWM0, PWM0, PWM0);
impl_pdm!(PDM, PDM, PDM);
impl_qdec!(QDEC, QDEC, QDEC);
impl_rng!(RNG, RNG, RNG);
impl_timer!(TIMER0, TIMER0, TIMER0);
impl_timer!(TIMER1, TIMER1, TIMER1);
impl_timer!(TIMER2, TIMER2, TIMER2);

View File

@ -150,6 +150,12 @@ impl_twis!(TWISPI0, TWIS0, TWIM0_TWIS0_TWI0_SPIM0_SPIS0_SPI0);
impl_pwm!(PWM0, PWM0, PWM0);
impl_pdm!(PDM, PDM, PDM);
impl_qdec!(QDEC, QDEC, QDEC);
impl_rng!(RNG, RNG, RNG);
impl_timer!(TIMER0, TIMER0, TIMER0);
impl_timer!(TIMER1, TIMER1, TIMER1);
impl_timer!(TIMER2, TIMER2, TIMER2);

View File

@ -153,6 +153,10 @@ impl_timer!(TIMER1, TIMER1, TIMER1);
impl_timer!(TIMER2, TIMER2, TIMER2);
impl_timer!(TIMER3, TIMER3, TIMER3, extended);
impl_qdec!(QDEC, QDEC, QDEC);
impl_rng!(RNG, RNG, RNG);
impl_pin!(P0_00, 0, 0);
impl_pin!(P0_01, 0, 1);
impl_pin!(P0_02, 0, 2);

View File

@ -146,6 +146,9 @@ embassy_hal_common::peripherals! {
// I2S
I2S,
// PDM
PDM,
}
impl_uarte!(UARTE0, UARTE0, UARTE0_UART0);
@ -168,6 +171,12 @@ impl_pwm!(PWM0, PWM0, PWM0);
impl_pwm!(PWM1, PWM1, PWM1);
impl_pwm!(PWM2, PWM2, PWM2);
impl_pdm!(PDM, PDM, PDM);
impl_qdec!(QDEC, QDEC, QDEC);
impl_rng!(RNG, RNG, RNG);
impl_timer!(TIMER0, TIMER0, TIMER0);
impl_timer!(TIMER1, TIMER1, TIMER1);
impl_timer!(TIMER2, TIMER2, TIMER2);

View File

@ -197,6 +197,12 @@ impl_pwm!(PWM1, PWM1, PWM1);
impl_pwm!(PWM2, PWM2, PWM2);
impl_pwm!(PWM3, PWM3, PWM3);
impl_pdm!(PDM, PDM, PDM);
impl_qdec!(QDEC, QDEC, QDEC);
impl_rng!(RNG, RNG, RNG);
impl_timer!(TIMER0, TIMER0, TIMER0);
impl_timer!(TIMER1, TIMER1, TIMER1);
impl_timer!(TIMER2, TIMER2, TIMER2);

View File

@ -208,6 +208,12 @@ impl_timer!(TIMER4, TIMER4, TIMER4, extended);
impl_qspi!(QSPI, QSPI, QSPI);
impl_pdm!(PDM, PDM, PDM);
impl_qdec!(QDEC, QDEC, QDEC);
impl_rng!(RNG, RNG, RNG);
impl_pin!(P0_00, 0, 0);
impl_pin!(P0_01, 0, 1);
impl_pin!(P0_02, 0, 2);

View File

@ -34,10 +34,10 @@ pub mod pac {
nvmc_ns as nvmc,
oscillators_ns as oscillators,
p0_ns as p0,
pdm0_ns as pdm0,
pdm0_ns as pdm,
power_ns as power,
pwm0_ns as pwm0,
qdec0_ns as qdec0,
qdec0_ns as qdec,
qspi_ns as qspi,
regulators_ns as regulators,
reset_ns as reset,
@ -250,6 +250,16 @@ embassy_hal_common::peripherals! {
TIMER1,
TIMER2,
// QSPI
QSPI,
// PDM
PDM0,
// QDEC
QDEC0,
QDEC1,
// GPIOTE
GPIOTE_CH0,
GPIOTE_CH1,
@ -393,6 +403,13 @@ impl_timer!(TIMER0, TIMER0, TIMER0);
impl_timer!(TIMER1, TIMER1, TIMER1);
impl_timer!(TIMER2, TIMER2, TIMER2);
impl_qspi!(QSPI, QSPI, QSPI);
impl_pdm!(PDM0, PDM0, PDM0);
impl_qdec!(QDEC0, QDEC0, QDEC0);
impl_qdec!(QDEC1, QDEC1, QDEC1);
impl_pin!(P0_00, 0, 0);
impl_pin!(P0_01, 0, 1);
#[cfg(feature = "nfc-pins-as-gpio")]

View File

@ -127,6 +127,9 @@ embassy_hal_common::peripherals! {
// SAADC
SAADC,
// RNG
RNG,
// PWM
PWM0,
PWM1,
@ -252,6 +255,8 @@ impl_timer!(TIMER0, TIMER0, TIMER0);
impl_timer!(TIMER1, TIMER1, TIMER1);
impl_timer!(TIMER2, TIMER2, TIMER2);
impl_rng!(RNG, RNG, RNG);
impl_pin!(P0_00, 0, 0);
impl_pin!(P0_01, 0, 1);
impl_pin!(P0_02, 0, 2);

View File

@ -301,6 +301,8 @@ impl_pwm!(PWM1, PWM1, PWM1);
impl_pwm!(PWM2, PWM2, PWM2);
impl_pwm!(PWM3, PWM3, PWM3);
impl_pdm!(PDM, PDM, PDM);
impl_timer!(TIMER0, TIMER0, TIMER0);
impl_timer!(TIMER1, TIMER1, TIMER1);
impl_timer!(TIMER2, TIMER2, TIMER2);

View File

@ -315,6 +315,7 @@ impl<'d, C: Channel, T: GpioPin> OutputChannel<'d, C, T> {
// =======================
#[must_use = "futures do nothing unless you `.await` or poll them"]
pub(crate) struct PortInputFuture<'a> {
pin: PeripheralRef<'a, AnyPin>,
}

View File

@ -14,7 +14,7 @@ use embassy_hal_common::drop::OnDrop;
use embassy_hal_common::{into_ref, PeripheralRef};
use crate::gpio::{AnyPin, Pin as GpioPin};
use crate::interrupt::Interrupt;
use crate::interrupt::{self, Interrupt};
use crate::pac::i2s::RegisterBlock;
use crate::util::{slice_in_ram_or, slice_ptr_parts};
use crate::{Peripheral, EASY_DMA_SIZE};
@ -363,10 +363,39 @@ impl From<Channels> for u8 {
}
}
/// Interrupt handler.
pub struct InterruptHandler<T: Instance> {
_phantom: PhantomData<T>,
}
impl<T: Instance> interrupt::Handler<T::Interrupt> for InterruptHandler<T> {
unsafe fn on_interrupt() {
let device = Device::<T>::new();
let s = T::state();
if device.is_tx_ptr_updated() {
trace!("TX INT");
s.tx_waker.wake();
device.disable_tx_ptr_interrupt();
}
if device.is_rx_ptr_updated() {
trace!("RX INT");
s.rx_waker.wake();
device.disable_rx_ptr_interrupt();
}
if device.is_stopped() {
trace!("STOPPED INT");
s.stop_waker.wake();
device.disable_stopped_interrupt();
}
}
}
/// I2S driver.
pub struct I2S<'d, T: Instance> {
i2s: PeripheralRef<'d, T>,
irq: PeripheralRef<'d, T::Interrupt>,
mck: Option<PeripheralRef<'d, AnyPin>>,
sck: PeripheralRef<'d, AnyPin>,
lrck: PeripheralRef<'d, AnyPin>,
@ -378,19 +407,18 @@ pub struct I2S<'d, T: Instance> {
impl<'d, T: Instance> I2S<'d, T> {
/// Create a new I2S in master mode
pub fn master(
pub fn new_master(
i2s: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
mck: impl Peripheral<P = impl GpioPin> + 'd,
sck: impl Peripheral<P = impl GpioPin> + 'd,
lrck: impl Peripheral<P = impl GpioPin> + 'd,
master_clock: MasterClock,
config: Config,
) -> Self {
into_ref!(i2s, irq, mck, sck, lrck);
into_ref!(i2s, mck, sck, lrck);
Self {
i2s,
irq,
mck: Some(mck.map_into()),
sck: sck.map_into(),
lrck: lrck.map_into(),
@ -402,17 +430,16 @@ impl<'d, T: Instance> I2S<'d, T> {
}
/// Create a new I2S in slave mode
pub fn slave(
pub fn new_slave(
i2s: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
sck: impl Peripheral<P = impl GpioPin> + 'd,
lrck: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Self {
into_ref!(i2s, irq, sck, lrck);
into_ref!(i2s, sck, lrck);
Self {
i2s,
irq,
mck: None,
sck: sck.map_into(),
lrck: lrck.map_into(),
@ -537,9 +564,8 @@ impl<'d, T: Instance> I2S<'d, T> {
}
fn setup_interrupt(&self) {
self.irq.set_handler(Self::on_interrupt);
self.irq.unpend();
self.irq.enable();
unsafe { T::Interrupt::steal() }.unpend();
unsafe { T::Interrupt::steal() }.enable();
let device = Device::<T>::new();
device.disable_tx_ptr_interrupt();
@ -555,29 +581,6 @@ impl<'d, T: Instance> I2S<'d, T> {
device.enable_stopped_interrupt();
}
fn on_interrupt(_: *mut ()) {
let device = Device::<T>::new();
let s = T::state();
if device.is_tx_ptr_updated() {
trace!("TX INT");
s.tx_waker.wake();
device.disable_tx_ptr_interrupt();
}
if device.is_rx_ptr_updated() {
trace!("RX INT");
s.rx_waker.wake();
device.disable_rx_ptr_interrupt();
}
if device.is_stopped() {
trace!("STOPPED INT");
s.stop_waker.wake();
device.disable_stopped_interrupt();
}
}
async fn stop() {
compiler_fence(Ordering::SeqCst);
@ -1168,7 +1171,7 @@ pub(crate) mod sealed {
}
}
/// I2S peripehral instance.
/// I2S peripheral instance.
pub trait Instance: Peripheral<P = Self> + sealed::Instance + 'static + Send {
/// Interrupt for this peripheral.
type Interrupt: Interrupt;

View File

@ -37,7 +37,6 @@ pub(crate) mod util;
#[cfg(feature = "_time-driver")]
mod time_driver;
#[cfg(feature = "nightly")]
pub mod buffered_uarte;
pub mod gpio;
#[cfg(feature = "gpiote")]
@ -48,19 +47,21 @@ pub mod nvmc;
#[cfg(any(
feature = "nrf52810",
feature = "nrf52811",
feature = "nrf52832",
feature = "nrf52833",
feature = "nrf52840",
feature = "_nrf5340-app",
feature = "_nrf9160"
))]
pub mod pdm;
pub mod ppi;
#[cfg(not(any(feature = "nrf52805", feature = "nrf52820", feature = "_nrf5340-net")))]
pub mod pwm;
#[cfg(not(any(feature = "nrf51", feature = "_nrf9160", feature = "_nrf5340")))]
#[cfg(not(any(feature = "nrf51", feature = "_nrf9160", feature = "_nrf5340-net")))]
pub mod qdec;
#[cfg(feature = "nrf52840")]
#[cfg(any(feature = "nrf52840", feature = "_nrf5340-app"))]
pub mod qspi;
#[cfg(not(any(feature = "_nrf5340", feature = "_nrf9160")))]
#[cfg(not(any(feature = "_nrf5340-app", feature = "_nrf9160")))]
pub mod rng;
#[cfg(not(any(feature = "nrf52820", feature = "_nrf5340-net")))]
pub mod saadc;
@ -96,14 +97,39 @@ pub mod wdt;
#[cfg_attr(feature = "_nrf9160", path = "chips/nrf9160.rs")]
mod chip;
pub use chip::EASY_DMA_SIZE;
pub mod interrupt {
//! nRF interrupts for cortex-m devices.
//! Interrupt definitions and macros to bind them.
pub use cortex_m::interrupt::{CriticalSection, Mutex};
pub use embassy_cortex_m::interrupt::*;
pub use embassy_cortex_m::interrupt::{Binding, Handler, Interrupt, InterruptExt, Priority};
pub use crate::chip::irqs::*;
/// Macro to bind interrupts to handlers.
///
/// This defines the right interrupt handlers, and creates a unit struct (like `struct Irqs;`)
/// and implements the right [`Binding`]s for it. You can pass this struct to drivers to
/// prove at compile-time that the right interrupts have been bound.
// developer note: this macro can't be in `embassy-cortex-m` due to the use of `$crate`.
#[macro_export]
macro_rules! bind_interrupts {
($vis:vis struct $name:ident { $($irq:ident => $($handler:ty),*;)* }) => {
$vis struct $name;
$(
#[allow(non_snake_case)]
#[no_mangle]
unsafe extern "C" fn $irq() {
$(
<$handler as $crate::interrupt::Handler<$crate::interrupt::$irq>>::on_interrupt();
)*
}
$(
unsafe impl $crate::interrupt::Binding<$crate::interrupt::$irq, $handler> for $name {}
)*
)*
};
}
}
// Reexports
@ -112,7 +138,7 @@ pub mod interrupt {
pub use chip::pac;
#[cfg(not(feature = "unstable-pac"))]
pub(crate) use chip::pac;
pub use chip::{peripherals, Peripherals};
pub use chip::{peripherals, Peripherals, EASY_DMA_SIZE};
pub use embassy_cortex_m::executor;
pub use embassy_cortex_m::interrupt::_export::interrupt;
pub use embassy_hal_common::{into_ref, Peripheral, PeripheralRef};

View File

@ -1,25 +1,37 @@
//! Pulse Density Modulation (PDM) mirophone driver.
#![macro_use]
use core::marker::PhantomData;
use core::sync::atomic::{compiler_fence, Ordering};
use core::task::Poll;
use embassy_cortex_m::interrupt::Interrupt;
use embassy_hal_common::drop::OnDrop;
use embassy_hal_common::{into_ref, PeripheralRef};
use embassy_sync::waitqueue::AtomicWaker;
use futures::future::poll_fn;
use crate::chip::EASY_DMA_SIZE;
use crate::gpio::sealed::Pin;
use crate::gpio::{AnyPin, Pin as GpioPin};
use crate::interrupt::{self, InterruptExt};
use crate::peripherals::PDM;
use crate::{pac, Peripheral};
use crate::Peripheral;
/// Interrupt handler.
pub struct InterruptHandler<T: Instance> {
_phantom: PhantomData<T>,
}
impl<T: Instance> interrupt::Handler<T::Interrupt> for InterruptHandler<T> {
unsafe fn on_interrupt() {
T::regs().intenclr.write(|w| w.end().clear());
T::state().waker.wake();
}
}
/// PDM microphone interface
pub struct Pdm<'d> {
irq: PeripheralRef<'d, interrupt::PDM>,
phantom: PhantomData<&'d PDM>,
pub struct Pdm<'d, T: Instance> {
_peri: PeripheralRef<'d, T>,
}
/// PDM error.
@ -35,32 +47,30 @@ pub enum Error {
NotRunning,
}
static WAKER: AtomicWaker = AtomicWaker::new();
static DUMMY_BUFFER: [i16; 1] = [0; 1];
impl<'d> Pdm<'d> {
impl<'d, T: Instance> Pdm<'d, T> {
/// Create PDM driver
pub fn new(
pdm: impl Peripheral<P = PDM> + 'd,
irq: impl Peripheral<P = interrupt::PDM> + 'd,
pdm: impl Peripheral<P = T> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
clk: impl Peripheral<P = impl GpioPin> + 'd,
din: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Self {
into_ref!(clk, din);
Self::new_inner(pdm, irq, clk.map_into(), din.map_into(), config)
into_ref!(pdm, clk, din);
Self::new_inner(pdm, clk.map_into(), din.map_into(), config)
}
fn new_inner(
_pdm: impl Peripheral<P = PDM> + 'd,
irq: impl Peripheral<P = interrupt::PDM> + 'd,
pdm: PeripheralRef<'d, T>,
clk: PeripheralRef<'d, AnyPin>,
din: PeripheralRef<'d, AnyPin>,
config: Config,
) -> Self {
into_ref!(irq);
into_ref!(pdm);
let r = Self::regs();
let r = T::regs();
// setup gpio pins
din.conf().write(|w| w.input().set_bit());
@ -84,26 +94,18 @@ impl<'d> Pdm<'d> {
r.gainr.write(|w| w.gainr().default_gain());
// IRQ
irq.disable();
irq.set_handler(|_| {
let r = Self::regs();
r.intenclr.write(|w| w.end().clear());
WAKER.wake();
});
irq.enable();
unsafe { T::Interrupt::steal() }.unpend();
unsafe { T::Interrupt::steal() }.enable();
r.enable.write(|w| w.enable().set_bit());
Self {
phantom: PhantomData,
irq,
}
Self { _peri: pdm }
}
/// Start sampling microphon data into a dummy buffer
/// Usefull to start the microphon and keep it active between recording samples
pub async fn start(&mut self) {
let r = Self::regs();
let r = T::regs();
// start dummy sampling because microphon needs some setup time
r.sample
@ -113,13 +115,13 @@ impl<'d> Pdm<'d> {
.maxcnt
.write(|w| unsafe { w.buffsize().bits(DUMMY_BUFFER.len() as _) });
r.tasks_start.write(|w| w.tasks_start().set_bit());
r.tasks_start.write(|w| unsafe { w.bits(1) });
}
/// Stop sampling microphon data inta a dummy buffer
pub async fn stop(&mut self) {
let r = Self::regs();
r.tasks_stop.write(|w| w.tasks_stop().set_bit());
let r = T::regs();
r.tasks_stop.write(|w| unsafe { w.bits(1) });
r.events_started.reset();
}
@ -132,9 +134,9 @@ impl<'d> Pdm<'d> {
return Err(Error::BufferTooLong);
}
let r = Self::regs();
let r = T::regs();
if r.events_started.read().events_started().bit_is_clear() {
if r.events_started.read().bits() == 0 {
return Err(Error::NotRunning);
}
@ -179,7 +181,7 @@ impl<'d> Pdm<'d> {
}
async fn wait_for_sample() {
let r = Self::regs();
let r = T::regs();
r.events_end.reset();
r.intenset.write(|w| w.end().set());
@ -187,8 +189,8 @@ impl<'d> Pdm<'d> {
compiler_fence(Ordering::SeqCst);
poll_fn(|cx| {
WAKER.register(cx.waker());
if r.events_end.read().events_end().bit_is_set() {
T::state().waker.register(cx.waker());
if r.events_end.read().bits() != 0 {
return Poll::Ready(());
}
Poll::Pending
@ -197,10 +199,6 @@ impl<'d> Pdm<'d> {
compiler_fence(Ordering::SeqCst);
}
fn regs() -> &'static pac::pdm::RegisterBlock {
unsafe { &*pac::PDM::ptr() }
}
}
/// PDM microphone driver Config
@ -238,13 +236,11 @@ pub enum Edge {
LeftFalling,
}
impl<'d> Drop for Pdm<'d> {
impl<'d, T: Instance> Drop for Pdm<'d, T> {
fn drop(&mut self) {
let r = Self::regs();
let r = T::regs();
r.tasks_stop.write(|w| w.tasks_stop().set_bit());
self.irq.disable();
r.tasks_stop.write(|w| unsafe { w.bits(1) });
r.enable.write(|w| w.enable().disabled());
@ -252,3 +248,48 @@ impl<'d> Drop for Pdm<'d> {
r.psel.clk.reset();
}
}
pub(crate) mod sealed {
use embassy_sync::waitqueue::AtomicWaker;
/// Peripheral static state
pub struct State {
pub waker: AtomicWaker,
}
impl State {
pub const fn new() -> Self {
Self {
waker: AtomicWaker::new(),
}
}
}
pub trait Instance {
fn regs() -> &'static crate::pac::pdm::RegisterBlock;
fn state() -> &'static State;
}
}
/// PDM peripheral instance.
pub trait Instance: Peripheral<P = Self> + sealed::Instance + 'static + Send {
/// Interrupt for this peripheral.
type Interrupt: Interrupt;
}
macro_rules! impl_pdm {
($type:ident, $pac_type:ident, $irq:ident) => {
impl crate::pdm::sealed::Instance for peripherals::$type {
fn regs() -> &'static crate::pac::pdm::RegisterBlock {
unsafe { &*pac::$pac_type::ptr() }
}
fn state() -> &'static crate::pdm::sealed::State {
static STATE: crate::pdm::sealed::State = crate::pdm::sealed::State::new();
&STATE
}
}
impl crate::pdm::Instance for peripherals::$type {
type Interrupt = crate::interrupt::$irq;
}
};
}

View File

@ -6,7 +6,7 @@ use crate::{pac, Peripheral};
const DPPI_ENABLE_BIT: u32 = 0x8000_0000;
const DPPI_CHANNEL_MASK: u32 = 0x0000_00FF;
fn regs() -> &'static pac::dppic::RegisterBlock {
pub(crate) fn regs() -> &'static pac::dppic::RegisterBlock {
unsafe { &*pac::DPPIC::ptr() }
}

View File

@ -17,16 +17,16 @@
use core::ptr::NonNull;
use embassy_hal_common::{impl_peripheral, PeripheralRef};
use embassy_hal_common::{impl_peripheral, into_ref, PeripheralRef};
use crate::{peripherals, Peripheral};
#[cfg(feature = "_dppi")]
mod dppi;
#[cfg(feature = "_ppi")]
mod ppi;
#[cfg_attr(feature = "_dppi", path = "dppi.rs")]
#[cfg_attr(feature = "_ppi", path = "ppi.rs")]
mod _version;
pub(crate) use _version::*;
/// An instance of the Programmable peripheral interconnect on nRF devices.
/// PPI channel driver.
pub struct Ppi<'d, C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize> {
ch: PeripheralRef<'d, C>,
#[cfg(feature = "_dppi")]
@ -35,6 +35,88 @@ pub struct Ppi<'d, C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize
tasks: [Task; TASK_COUNT],
}
/// PPI channel group driver.
pub struct PpiGroup<'d, G: Group> {
g: PeripheralRef<'d, G>,
}
impl<'d, G: Group> PpiGroup<'d, G> {
/// Create a new PPI group driver.
///
/// The group is initialized as containing no channels.
pub fn new(g: impl Peripheral<P = G> + 'd) -> Self {
into_ref!(g);
let r = regs();
let n = g.number();
r.chg[n].write(|w| unsafe { w.bits(0) });
Self { g }
}
/// Add a PPI channel to this group.
///
/// If the channel is already in the group, this is a no-op.
pub fn add_channel<C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize>(
&mut self,
ch: &Ppi<'_, C, EVENT_COUNT, TASK_COUNT>,
) {
let r = regs();
let ng = self.g.number();
let nc = ch.ch.number();
r.chg[ng].modify(|r, w| unsafe { w.bits(r.bits() | 1 << nc) });
}
/// Remove a PPI channel from this group.
///
/// If the channel is already not in the group, this is a no-op.
pub fn remove_channel<C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize>(
&mut self,
ch: &Ppi<'_, C, EVENT_COUNT, TASK_COUNT>,
) {
let r = regs();
let ng = self.g.number();
let nc = ch.ch.number();
r.chg[ng].modify(|r, w| unsafe { w.bits(r.bits() & !(1 << nc)) });
}
/// Enable all the channels in this group.
pub fn enable_all(&mut self) {
let n = self.g.number();
regs().tasks_chg[n].en.write(|w| unsafe { w.bits(1) });
}
/// Disable all the channels in this group.
pub fn disable_all(&mut self) {
let n = self.g.number();
regs().tasks_chg[n].dis.write(|w| unsafe { w.bits(1) });
}
/// Get a reference to the "enable all" task.
///
/// When triggered, it will enable all the channels in this group.
pub fn task_enable_all(&self) -> Task {
let n = self.g.number();
Task::from_reg(&regs().tasks_chg[n].en)
}
/// Get a reference to the "disable all" task.
///
/// When triggered, it will disable all the channels in this group.
pub fn task_disable_all(&self) -> Task {
let n = self.g.number();
Task::from_reg(&regs().tasks_chg[n].dis)
}
}
impl<'d, G: Group> Drop for PpiGroup<'d, G> {
fn drop(&mut self) {
let r = regs();
let n = self.g.number();
r.chg[n].write(|w| unsafe { w.bits(0) });
}
}
#[cfg(feature = "_dppi")]
const REGISTER_DPPI_CONFIG_OFFSET: usize = 0x80 / core::mem::size_of::<u32>();
@ -112,7 +194,7 @@ pub(crate) mod sealed {
}
/// Interface for PPI channels.
pub trait Channel: sealed::Channel + Peripheral<P = Self> + Sized {
pub trait Channel: sealed::Channel + Peripheral<P = Self> + Sized + 'static {
/// Returns the number of the channel
fn number(&self) -> usize;
}
@ -130,7 +212,7 @@ pub trait StaticChannel: Channel + Into<AnyStaticChannel> {
}
/// Interface for a group of PPI channels.
pub trait Group: sealed::Group + Sized {
pub trait Group: sealed::Group + Peripheral<P = Self> + Into<AnyGroup> + Sized + 'static {
/// Returns the number of the group.
fn number(&self) -> usize;
/// Convert into a type erased group.
@ -248,6 +330,12 @@ macro_rules! impl_group {
$number
}
}
impl From<peripherals::$type> for crate::ppi::AnyGroup {
fn from(val: peripherals::$type) -> Self {
crate::ppi::Group::degrade(val)
}
}
};
}

View File

@ -14,7 +14,7 @@ impl Event {
}
}
fn regs() -> &'static pac::ppi::RegisterBlock {
pub(crate) fn regs() -> &'static pac::ppi::RegisterBlock {
unsafe { &*pac::PPI::ptr() }
}

View File

@ -1,20 +1,22 @@
//! Quadrature decoder (QDEC) driver.
#![macro_use]
use core::future::poll_fn;
use core::marker::PhantomData;
use core::task::Poll;
use embassy_cortex_m::interrupt::Interrupt;
use embassy_hal_common::{into_ref, PeripheralRef};
use embassy_sync::waitqueue::AtomicWaker;
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, Peripheral};
use crate::{interrupt, Peripheral};
/// Quadrature decoder driver.
pub struct Qdec<'d> {
_p: PeripheralRef<'d, QDEC>,
pub struct Qdec<'d, T: Instance> {
_p: PeripheralRef<'d, T>,
}
/// QDEC config
@ -44,44 +46,52 @@ impl Default for Config {
}
}
static WAKER: AtomicWaker = AtomicWaker::new();
/// Interrupt handler.
pub struct InterruptHandler<T: Instance> {
_phantom: PhantomData<T>,
}
impl<'d> Qdec<'d> {
impl<T: Instance> interrupt::Handler<T::Interrupt> for InterruptHandler<T> {
unsafe fn on_interrupt() {
T::regs().intenclr.write(|w| w.reportrdy().clear());
T::state().waker.wake();
}
}
impl<'d, T: Instance> Qdec<'d, T> {
/// Create a new QDEC.
pub fn new(
qdec: impl Peripheral<P = QDEC> + 'd,
irq: impl Peripheral<P = interrupt::QDEC> + 'd,
qdec: impl Peripheral<P = T> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
a: impl Peripheral<P = impl GpioPin> + 'd,
b: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Self {
into_ref!(a, b);
Self::new_inner(qdec, irq, a.map_into(), b.map_into(), None, config)
into_ref!(qdec, a, b);
Self::new_inner(qdec, a.map_into(), b.map_into(), None, config)
}
/// Create a new QDEC, with a pin for LED output.
pub fn new_with_led(
qdec: impl Peripheral<P = QDEC> + 'd,
irq: impl Peripheral<P = interrupt::QDEC> + 'd,
qdec: impl Peripheral<P = T> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
a: impl Peripheral<P = impl GpioPin> + 'd,
b: impl Peripheral<P = impl GpioPin> + 'd,
led: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Self {
into_ref!(a, b, led);
Self::new_inner(qdec, irq, a.map_into(), b.map_into(), Some(led.map_into()), config)
into_ref!(qdec, a, b, led);
Self::new_inner(qdec, a.map_into(), b.map_into(), Some(led.map_into()), config)
}
fn new_inner(
p: impl Peripheral<P = QDEC> + 'd,
irq: impl Peripheral<P = interrupt::QDEC> + 'd,
p: PeripheralRef<'d, T>,
a: PeripheralRef<'d, AnyPin>,
b: PeripheralRef<'d, AnyPin>,
led: Option<PeripheralRef<'d, AnyPin>>,
config: Config,
) -> Self {
into_ref!(p, irq);
let r = Self::regs();
let r = T::regs();
// Select pins.
a.conf().write(|w| w.input().connect().pull().pullup());
@ -124,20 +134,15 @@ impl<'d> Qdec<'d> {
SamplePeriod::_131ms => w.sampleper()._131ms(),
});
unsafe { T::Interrupt::steal() }.unpend();
unsafe { T::Interrupt::steal() }.enable();
// Enable peripheral
r.enable.write(|w| w.enable().set_bit());
// Start sampling
unsafe { r.tasks_start.write(|w| w.bits(1)) };
irq.disable();
irq.set_handler(|_| {
let r = Self::regs();
r.intenclr.write(|w| w.reportrdy().clear());
WAKER.wake();
});
irq.enable();
Self { _p: p }
}
@ -155,12 +160,12 @@ impl<'d> Qdec<'d> {
/// let delta = q.read().await;
/// ```
pub async fn read(&mut self) -> i16 {
let t = Self::regs();
let t = T::regs();
t.intenset.write(|w| w.reportrdy().set());
unsafe { t.tasks_readclracc.write(|w| w.bits(1)) };
let value = poll_fn(|cx| {
WAKER.register(cx.waker());
T::state().waker.register(cx.waker());
if t.events_reportrdy.read().bits() == 0 {
return Poll::Pending;
} else {
@ -172,10 +177,6 @@ impl<'d> Qdec<'d> {
.await;
value
}
fn regs() -> &'static pac::qdec::RegisterBlock {
unsafe { &*pac::QDEC::ptr() }
}
}
/// Sample period
@ -236,3 +237,48 @@ pub enum LedPolarity {
/// Active low (a low output turns on the LED).
ActiveLow,
}
pub(crate) mod sealed {
use embassy_sync::waitqueue::AtomicWaker;
/// Peripheral static state
pub struct State {
pub waker: AtomicWaker,
}
impl State {
pub const fn new() -> Self {
Self {
waker: AtomicWaker::new(),
}
}
}
pub trait Instance {
fn regs() -> &'static crate::pac::qdec::RegisterBlock;
fn state() -> &'static State;
}
}
/// qdec peripheral instance.
pub trait Instance: Peripheral<P = Self> + sealed::Instance + 'static + Send {
/// Interrupt for this peripheral.
type Interrupt: Interrupt;
}
macro_rules! impl_qdec {
($type:ident, $pac_type:ident, $irq:ident) => {
impl crate::qdec::sealed::Instance for peripherals::$type {
fn regs() -> &'static crate::pac::qdec::RegisterBlock {
unsafe { &*pac::$pac_type::ptr() }
}
fn state() -> &'static crate::qdec::sealed::State {
static STATE: crate::qdec::sealed::State = crate::qdec::sealed::State::new();
&STATE
}
}
impl crate::qdec::Instance for peripherals::$type {
type Interrupt = crate::interrupt::$irq;
}
};
}

View File

@ -3,19 +3,21 @@
#![macro_use]
use core::future::poll_fn;
use core::marker::PhantomData;
use core::ptr;
use core::task::Poll;
use embassy_hal_common::drop::OnDrop;
use embassy_hal_common::{into_ref, PeripheralRef};
use embedded_storage::nor_flash::{ErrorType, NorFlash, NorFlashError, NorFlashErrorKind, ReadNorFlash};
use crate::gpio::{self, Pin as GpioPin};
use crate::interrupt::{Interrupt, InterruptExt};
use crate::interrupt::{self, Interrupt, InterruptExt};
pub use crate::pac::qspi::ifconfig0::{
ADDRMODE_A as AddressMode, PPSIZE_A as WritePageSize, READOC_A as ReadOpcode, WRITEOC_A as WriteOpcode,
};
pub use crate::pac::qspi::ifconfig1::SPIMODE_A as SpiMode;
use crate::{pac, Peripheral};
use crate::Peripheral;
/// Deep power-down config.
pub struct DeepPowerDownConfig {
@ -82,6 +84,8 @@ pub struct Config {
pub spi_mode: SpiMode,
/// Addressing mode (24-bit or 32-bit)
pub address_mode: AddressMode,
/// Flash memory capacity in bytes. This is the value reported by the `embedded-storage` traits.
pub capacity: u32,
}
impl Default for Config {
@ -96,6 +100,7 @@ impl Default for Config {
sck_delay: 80,
spi_mode: SpiMode::MODE0,
address_mode: AddressMode::_24BIT,
capacity: 0,
}
}
}
@ -110,17 +115,35 @@ pub enum Error {
// TODO add "not in data memory" error and check for it
}
/// QSPI flash driver.
pub struct Qspi<'d, T: Instance, const FLASH_SIZE: usize> {
irq: PeripheralRef<'d, T::Interrupt>,
dpm_enabled: bool,
/// Interrupt handler.
pub struct InterruptHandler<T: Instance> {
_phantom: PhantomData<T>,
}
impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
impl<T: Instance> interrupt::Handler<T::Interrupt> for InterruptHandler<T> {
unsafe fn on_interrupt() {
let r = T::regs();
let s = T::state();
if r.events_ready.read().bits() != 0 {
s.waker.wake();
r.intenclr.write(|w| w.ready().clear());
}
}
}
/// QSPI flash driver.
pub struct Qspi<'d, T: Instance> {
_peri: PeripheralRef<'d, T>,
dpm_enabled: bool,
capacity: u32,
}
impl<'d, T: Instance> Qspi<'d, T> {
/// Create a new QSPI driver.
pub fn new(
_qspi: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
qspi: impl Peripheral<P = T> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
sck: impl Peripheral<P = impl GpioPin> + 'd,
csn: impl Peripheral<P = impl GpioPin> + 'd,
io0: impl Peripheral<P = impl GpioPin> + 'd,
@ -128,30 +151,31 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
io2: impl Peripheral<P = impl GpioPin> + 'd,
io3: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Qspi<'d, T, FLASH_SIZE> {
into_ref!(irq, sck, csn, io0, io1, io2, io3);
) -> Self {
into_ref!(qspi, sck, csn, io0, io1, io2, io3);
let r = T::regs();
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());
macro_rules! config_pin {
($pin:ident) => {
$pin.set_high();
$pin.conf().write(|w| {
w.dir().output();
w.drive().h0h1();
#[cfg(feature = "_nrf5340-s")]
w.mcusel().peripheral();
w
});
r.psel.$pin.write(|w| unsafe { w.bits($pin.psel_bits()) });
};
}
r.psel.sck.write(|w| unsafe { w.bits(sck.psel_bits()) });
r.psel.csn.write(|w| unsafe { w.bits(csn.psel_bits()) });
r.psel.io0.write(|w| unsafe { w.bits(io0.psel_bits()) });
r.psel.io1.write(|w| unsafe { w.bits(io1.psel_bits()) });
r.psel.io2.write(|w| unsafe { w.bits(io2.psel_bits()) });
r.psel.io3.write(|w| unsafe { w.bits(io3.psel_bits()) });
config_pin!(sck);
config_pin!(csn);
config_pin!(io0);
config_pin!(io1);
config_pin!(io2);
config_pin!(io3);
r.ifconfig0.write(|w| {
w.addrmode().variant(config.address_mode);
@ -183,16 +207,16 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
w
});
irq.set_handler(Self::on_interrupt);
irq.unpend();
irq.enable();
unsafe { T::Interrupt::steal() }.unpend();
unsafe { T::Interrupt::steal() }.enable();
// Enable it
r.enable.write(|w| w.enable().enabled());
let res = Self {
_peri: qspi,
dpm_enabled: config.deep_power_down.is_some(),
irq,
capacity: config.capacity,
};
r.events_ready.reset();
@ -205,16 +229,6 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
res
}
fn on_interrupt(_: *mut ()) {
let r = T::regs();
let s = T::state();
if r.events_ready.read().bits() != 0 {
s.ready_waker.wake();
r.intenclr.write(|w| w.ready().clear());
}
}
/// Do a custom QSPI instruction.
pub async fn custom_instruction(&mut self, opcode: u8, req: &[u8], resp: &mut [u8]) -> Result<(), Error> {
let ondrop = OnDrop::new(Self::blocking_wait_ready);
@ -303,7 +317,7 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
poll_fn(move |cx| {
let r = T::regs();
let s = T::state();
s.ready_waker.register(cx.waker());
s.waker.register(cx.waker());
if r.events_ready.read().bits() != 0 {
return Poll::Ready(());
}
@ -321,17 +335,15 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
}
}
fn start_read(&mut self, address: usize, data: &mut [u8]) -> Result<(), Error> {
fn start_read(&mut self, address: u32, data: &mut [u8]) -> Result<(), Error> {
// TODO: Return these as errors instead.
assert_eq!(data.as_ptr() as u32 % 4, 0);
assert_eq!(data.len() as u32 % 4, 0);
assert_eq!(address as u32 % 4, 0);
if address > FLASH_SIZE {
return Err(Error::OutOfBounds);
}
assert_eq!(address % 4, 0);
let r = T::regs();
r.read.src.write(|w| unsafe { w.src().bits(address as u32) });
r.read.src.write(|w| unsafe { w.src().bits(address) });
r.read.dst.write(|w| unsafe { w.dst().bits(data.as_ptr() as u32) });
r.read.cnt.write(|w| unsafe { w.cnt().bits(data.len() as u32) });
@ -342,18 +354,15 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
Ok(())
}
fn start_write(&mut self, address: usize, data: &[u8]) -> Result<(), Error> {
fn start_write(&mut self, address: u32, data: &[u8]) -> Result<(), Error> {
// TODO: Return these as errors instead.
assert_eq!(data.as_ptr() as u32 % 4, 0);
assert_eq!(data.len() as u32 % 4, 0);
assert_eq!(address as u32 % 4, 0);
if address > FLASH_SIZE {
return Err(Error::OutOfBounds);
}
assert_eq!(address % 4, 0);
let r = T::regs();
r.write.src.write(|w| unsafe { w.src().bits(data.as_ptr() as u32) });
r.write.dst.write(|w| unsafe { w.dst().bits(address as u32) });
r.write.dst.write(|w| unsafe { w.dst().bits(address) });
r.write.cnt.write(|w| unsafe { w.cnt().bits(data.len() as u32) });
r.events_ready.reset();
@ -363,14 +372,12 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
Ok(())
}
fn start_erase(&mut self, address: usize) -> Result<(), Error> {
assert_eq!(address as u32 % 4096, 0);
if address > FLASH_SIZE {
return Err(Error::OutOfBounds);
}
fn start_erase(&mut self, address: u32) -> Result<(), Error> {
// TODO: Return these as errors instead.
assert_eq!(address % 4096, 0);
let r = T::regs();
r.erase.ptr.write(|w| unsafe { w.ptr().bits(address as u32) });
r.erase.ptr.write(|w| unsafe { w.ptr().bits(address) });
r.erase.len.write(|w| w.len()._4kb());
r.events_ready.reset();
@ -380,8 +387,12 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
Ok(())
}
/// Read data from the flash memory.
pub async fn read(&mut self, address: usize, data: &mut [u8]) -> Result<(), Error> {
/// Raw QSPI read.
///
/// The difference with `read` is that this does not do bounds checks
/// against the flash capacity. It is intended for use when QSPI is used as
/// a raw bus, not with flash memory.
pub async fn read_raw(&mut self, address: u32, data: &mut [u8]) -> Result<(), Error> {
let ondrop = OnDrop::new(Self::blocking_wait_ready);
self.start_read(address, data)?;
@ -392,8 +403,12 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
Ok(())
}
/// Write data to the flash memory.
pub async fn write(&mut self, address: usize, data: &[u8]) -> Result<(), Error> {
/// Raw QSPI write.
///
/// The difference with `write` is that this does not do bounds checks
/// against the flash capacity. It is intended for use when QSPI is used as
/// a raw bus, not with flash memory.
pub async fn write_raw(&mut self, address: u32, data: &[u8]) -> Result<(), Error> {
let ondrop = OnDrop::new(Self::blocking_wait_ready);
self.start_write(address, data)?;
@ -404,8 +419,46 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
Ok(())
}
/// Raw QSPI read, blocking version.
///
/// The difference with `blocking_read` is that this does not do bounds checks
/// against the flash capacity. It is intended for use when QSPI is used as
/// a raw bus, not with flash memory.
pub fn blocking_read_raw(&mut self, address: u32, data: &mut [u8]) -> Result<(), Error> {
self.start_read(address, data)?;
Self::blocking_wait_ready();
Ok(())
}
/// Raw QSPI write, blocking version.
///
/// The difference with `blocking_write` is that this does not do bounds checks
/// against the flash capacity. It is intended for use when QSPI is used as
/// a raw bus, not with flash memory.
pub fn blocking_write_raw(&mut self, address: u32, data: &[u8]) -> Result<(), Error> {
self.start_write(address, data)?;
Self::blocking_wait_ready();
Ok(())
}
/// Read data from the flash memory.
pub async fn read(&mut self, address: u32, data: &mut [u8]) -> Result<(), Error> {
self.bounds_check(address, data.len())?;
self.read_raw(address, data).await
}
/// Write data to the flash memory.
pub async fn write(&mut self, address: u32, data: &[u8]) -> Result<(), Error> {
self.bounds_check(address, data.len())?;
self.write_raw(address, data).await
}
/// Erase a sector on the flash memory.
pub async fn erase(&mut self, address: usize) -> Result<(), Error> {
pub async fn erase(&mut self, address: u32) -> Result<(), Error> {
if address >= self.capacity {
return Err(Error::OutOfBounds);
}
let ondrop = OnDrop::new(Self::blocking_wait_ready);
self.start_erase(address)?;
@ -417,28 +470,39 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
}
/// Read data from the flash memory, blocking version.
pub fn blocking_read(&mut self, address: usize, data: &mut [u8]) -> Result<(), Error> {
self.start_read(address, data)?;
Self::blocking_wait_ready();
Ok(())
pub fn blocking_read(&mut self, address: u32, data: &mut [u8]) -> Result<(), Error> {
self.bounds_check(address, data.len())?;
self.blocking_read_raw(address, data)
}
/// Write data to the flash memory, blocking version.
pub fn blocking_write(&mut self, address: usize, data: &[u8]) -> Result<(), Error> {
self.start_write(address, data)?;
Self::blocking_wait_ready();
Ok(())
pub fn blocking_write(&mut self, address: u32, data: &[u8]) -> Result<(), Error> {
self.bounds_check(address, data.len())?;
self.blocking_write_raw(address, data)
}
/// Erase a sector on the flash memory, blocking version.
pub fn blocking_erase(&mut self, address: usize) -> Result<(), Error> {
pub fn blocking_erase(&mut self, address: u32) -> Result<(), Error> {
if address >= self.capacity {
return Err(Error::OutOfBounds);
}
self.start_erase(address)?;
Self::blocking_wait_ready();
Ok(())
}
fn bounds_check(&self, address: u32, len: usize) -> Result<(), Error> {
let len_u32: u32 = len.try_into().map_err(|_| Error::OutOfBounds)?;
let end_address = address.checked_add(len_u32).ok_or(Error::OutOfBounds)?;
if end_address > self.capacity {
return Err(Error::OutOfBounds);
}
Ok(())
}
}
impl<'d, T: Instance, const FLASH_SIZE: usize> Drop for Qspi<'d, T, FLASH_SIZE> {
impl<'d, T: Instance> Drop for Qspi<'d, T> {
fn drop(&mut self) {
let r = T::regs();
@ -468,8 +532,6 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Drop for Qspi<'d, T, FLASH_SIZE>
r.enable.write(|w| w.enable().disabled());
self.irq.disable();
// Note: we do NOT deconfigure CSN here. If DPM is in use and we disconnect CSN,
// leaving it floating, the flash chip might read it as zero which would cause it to
// spuriously exit DPM.
@ -483,9 +545,7 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Drop for Qspi<'d, T, FLASH_SIZE>
}
}
use embedded_storage::nor_flash::{ErrorType, NorFlash, NorFlashError, NorFlashErrorKind, ReadNorFlash};
impl<'d, T: Instance, const FLASH_SIZE: usize> ErrorType for Qspi<'d, T, FLASH_SIZE> {
impl<'d, T: Instance> ErrorType for Qspi<'d, T> {
type Error = Error;
}
@ -495,66 +555,66 @@ impl NorFlashError for Error {
}
}
impl<'d, T: Instance, const FLASH_SIZE: usize> ReadNorFlash for Qspi<'d, T, FLASH_SIZE> {
impl<'d, T: Instance> ReadNorFlash for Qspi<'d, T> {
const READ_SIZE: usize = 4;
fn read(&mut self, offset: u32, bytes: &mut [u8]) -> Result<(), Self::Error> {
self.blocking_read(offset as usize, bytes)?;
self.blocking_read(offset, bytes)?;
Ok(())
}
fn capacity(&self) -> usize {
FLASH_SIZE
self.capacity as usize
}
}
impl<'d, T: Instance, const FLASH_SIZE: usize> NorFlash for Qspi<'d, T, FLASH_SIZE> {
impl<'d, T: Instance> NorFlash for Qspi<'d, T> {
const WRITE_SIZE: usize = 4;
const ERASE_SIZE: usize = 4096;
fn erase(&mut self, from: u32, to: u32) -> Result<(), Self::Error> {
for address in (from as usize..to as usize).step_by(<Self as NorFlash>::ERASE_SIZE) {
for address in (from..to).step_by(<Self as NorFlash>::ERASE_SIZE) {
self.blocking_erase(address)?;
}
Ok(())
}
fn write(&mut self, offset: u32, bytes: &[u8]) -> Result<(), Self::Error> {
self.blocking_write(offset as usize, bytes)?;
self.blocking_write(offset, bytes)?;
Ok(())
}
}
cfg_if::cfg_if! {
if #[cfg(feature = "nightly")]
{
use embedded_storage_async::nor_flash::{NorFlash as AsyncNorFlash, ReadNorFlash as AsyncReadNorFlash};
#[cfg(feature = "nightly")]
mod _eh1 {
use embedded_storage_async::nor_flash::{NorFlash as AsyncNorFlash, ReadNorFlash as AsyncReadNorFlash};
impl<'d, T: Instance, const FLASH_SIZE: usize> AsyncNorFlash for Qspi<'d, T, FLASH_SIZE> {
const WRITE_SIZE: usize = <Self as NorFlash>::WRITE_SIZE;
const ERASE_SIZE: usize = <Self as NorFlash>::ERASE_SIZE;
use super::*;
async fn write(&mut self, offset: u32, data: &[u8]) -> Result<(), Self::Error> {
self.write(offset as usize, data).await
}
impl<'d, T: Instance> AsyncNorFlash for Qspi<'d, T> {
const WRITE_SIZE: usize = <Self as NorFlash>::WRITE_SIZE;
const ERASE_SIZE: usize = <Self as NorFlash>::ERASE_SIZE;
async fn erase(&mut self, from: u32, to: u32) -> Result<(), Self::Error> {
for address in (from as usize..to as usize).step_by(<Self as AsyncNorFlash>::ERASE_SIZE) {
self.erase(address).await?
}
Ok(())
}
async fn write(&mut self, offset: u32, data: &[u8]) -> Result<(), Self::Error> {
self.write(offset, data).await
}
impl<'d, T: Instance, const FLASH_SIZE: usize> AsyncReadNorFlash for Qspi<'d, T, FLASH_SIZE> {
const READ_SIZE: usize = 4;
async fn read(&mut self, address: u32, data: &mut [u8]) -> Result<(), Self::Error> {
self.read(address as usize, data).await
async fn erase(&mut self, from: u32, to: u32) -> Result<(), Self::Error> {
for address in (from..to).step_by(<Self as AsyncNorFlash>::ERASE_SIZE) {
self.erase(address).await?
}
Ok(())
}
}
fn capacity(&self) -> usize {
FLASH_SIZE
}
impl<'d, T: Instance> AsyncReadNorFlash for Qspi<'d, T> {
const READ_SIZE: usize = 4;
async fn read(&mut self, address: u32, data: &mut [u8]) -> Result<(), Self::Error> {
self.read(address, data).await
}
fn capacity(&self) -> usize {
self.capacity as usize
}
}
}
@ -562,27 +622,27 @@ cfg_if::cfg_if! {
pub(crate) mod sealed {
use embassy_sync::waitqueue::AtomicWaker;
use super::*;
/// Peripheral static state
pub struct State {
pub ready_waker: AtomicWaker,
pub waker: AtomicWaker,
}
impl State {
pub const fn new() -> Self {
Self {
ready_waker: AtomicWaker::new(),
waker: AtomicWaker::new(),
}
}
}
pub trait Instance {
fn regs() -> &'static pac::qspi::RegisterBlock;
fn regs() -> &'static crate::pac::qspi::RegisterBlock;
fn state() -> &'static State;
}
}
/// QSPI peripheral instance.
pub trait Instance: Peripheral<P = Self> + sealed::Instance + 'static {
pub trait Instance: Peripheral<P = Self> + sealed::Instance + 'static + Send {
/// Interrupt for this peripheral.
type Interrupt: Interrupt;
}
@ -590,7 +650,7 @@ pub trait Instance: Peripheral<P = Self> + sealed::Instance + 'static {
macro_rules! impl_qspi {
($type:ident, $pac_type:ident, $irq:ident) => {
impl crate::qspi::sealed::Instance for peripherals::$type {
fn regs() -> &'static pac::qspi::RegisterBlock {
fn regs() -> &'static crate::pac::qspi::RegisterBlock {
unsafe { &*pac::$pac_type::ptr() }
}
fn state() -> &'static crate::qspi::sealed::State {

View File

@ -1,83 +1,48 @@
//! Random Number Generator (RNG) driver.
#![macro_use]
use core::future::poll_fn;
use core::marker::PhantomData;
use core::ptr;
use core::sync::atomic::{AtomicPtr, Ordering};
use core::task::Poll;
use embassy_cortex_m::interrupt::Interrupt;
use embassy_hal_common::drop::OnDrop;
use embassy_hal_common::{into_ref, PeripheralRef};
use embassy_sync::waitqueue::AtomicWaker;
use crate::interrupt::InterruptExt;
use crate::peripherals::RNG;
use crate::{interrupt, pac, Peripheral};
use crate::{interrupt, Peripheral};
impl RNG {
fn regs() -> &'static pac::rng::RegisterBlock {
unsafe { &*pac::RNG::ptr() }
}
/// Interrupt handler.
pub struct InterruptHandler<T: Instance> {
_phantom: PhantomData<T>,
}
static STATE: State = State {
ptr: AtomicPtr::new(ptr::null_mut()),
end: AtomicPtr::new(ptr::null_mut()),
waker: AtomicWaker::new(),
};
impl<T: Instance> interrupt::Handler<T::Interrupt> for InterruptHandler<T> {
unsafe fn on_interrupt() {
let s = T::state();
let r = T::regs();
struct State {
ptr: AtomicPtr<u8>,
end: AtomicPtr<u8>,
waker: AtomicWaker,
}
/// A wrapper around an nRF RNG peripheral.
///
/// It has a non-blocking API, and a blocking api through `rand`.
pub struct Rng<'d> {
irq: PeripheralRef<'d, interrupt::RNG>,
}
impl<'d> Rng<'d> {
/// Creates a new RNG driver from the `RNG` peripheral and interrupt.
///
/// SAFETY: The future returned from `fill_bytes` must not have its lifetime end without running its destructor,
/// e.g. using `mem::forget`.
///
/// The synchronous API is safe.
pub fn new(_rng: impl Peripheral<P = RNG> + 'd, irq: impl Peripheral<P = interrupt::RNG> + 'd) -> Self {
into_ref!(irq);
let this = Self { irq };
this.stop();
this.disable_irq();
this.irq.set_handler(Self::on_interrupt);
this.irq.unpend();
this.irq.enable();
this
}
fn on_interrupt(_: *mut ()) {
// Clear the event.
RNG::regs().events_valrdy.reset();
r.events_valrdy.reset();
// Mutate the slice within a critical section,
// so that the future isn't dropped in between us loading the pointer and actually dereferencing it.
let (ptr, end) = critical_section::with(|_| {
let ptr = STATE.ptr.load(Ordering::Relaxed);
let ptr = s.ptr.load(Ordering::Relaxed);
// We need to make sure we haven't already filled the whole slice,
// in case the interrupt fired again before the executor got back to the future.
let end = STATE.end.load(Ordering::Relaxed);
let end = s.end.load(Ordering::Relaxed);
if !ptr.is_null() && ptr != end {
// If the future was dropped, the pointer would have been set to null,
// so we're still good to mutate the slice.
// The safety contract of `Rng::new` means that the future can't have been dropped
// without calling its destructor.
unsafe {
*ptr = RNG::regs().value.read().value().bits();
*ptr = r.value.read().value().bits();
}
}
(ptr, end)
@ -90,15 +55,15 @@ impl<'d> Rng<'d> {
}
let new_ptr = unsafe { ptr.add(1) };
match STATE
match s
.ptr
.compare_exchange(ptr, new_ptr, Ordering::Relaxed, Ordering::Relaxed)
{
Ok(_) => {
let end = STATE.end.load(Ordering::Relaxed);
let end = s.end.load(Ordering::Relaxed);
// It doesn't matter if `end` was changed under our feet, because then this will just be false.
if new_ptr == end {
STATE.waker.wake();
s.waker.wake();
}
}
Err(_) => {
@ -107,21 +72,53 @@ impl<'d> Rng<'d> {
}
}
}
}
/// A wrapper around an nRF RNG peripheral.
///
/// It has a non-blocking API, and a blocking api through `rand`.
pub struct Rng<'d, T: Instance> {
_peri: PeripheralRef<'d, T>,
}
impl<'d, T: Instance> Rng<'d, T> {
/// Creates a new RNG driver from the `RNG` peripheral and interrupt.
///
/// SAFETY: The future returned from `fill_bytes` must not have its lifetime end without running its destructor,
/// e.g. using `mem::forget`.
///
/// The synchronous API is safe.
pub fn new(
rng: impl Peripheral<P = T> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
) -> Self {
into_ref!(rng);
let this = Self { _peri: rng };
this.stop();
this.disable_irq();
unsafe { T::Interrupt::steal() }.unpend();
unsafe { T::Interrupt::steal() }.enable();
this
}
fn stop(&self) {
RNG::regs().tasks_stop.write(|w| unsafe { w.bits(1) })
T::regs().tasks_stop.write(|w| unsafe { w.bits(1) })
}
fn start(&self) {
RNG::regs().tasks_start.write(|w| unsafe { w.bits(1) })
T::regs().tasks_start.write(|w| unsafe { w.bits(1) })
}
fn enable_irq(&self) {
RNG::regs().intenset.write(|w| w.valrdy().set());
T::regs().intenset.write(|w| w.valrdy().set());
}
fn disable_irq(&self) {
RNG::regs().intenclr.write(|w| w.valrdy().clear());
T::regs().intenclr.write(|w| w.valrdy().clear());
}
/// Enable or disable the RNG's bias correction.
@ -131,7 +128,7 @@ impl<'d> Rng<'d> {
///
/// Defaults to disabled.
pub fn set_bias_correction(&self, enable: bool) {
RNG::regs().config.write(|w| w.dercen().bit(enable))
T::regs().config.write(|w| w.dercen().bit(enable))
}
/// Fill the buffer with random bytes.
@ -140,11 +137,13 @@ impl<'d> Rng<'d> {
return; // Nothing to fill
}
let s = T::state();
let range = dest.as_mut_ptr_range();
// Even if we've preempted the interrupt, it can't preempt us again,
// so we don't need to worry about the order we write these in.
STATE.ptr.store(range.start, Ordering::Relaxed);
STATE.end.store(range.end, Ordering::Relaxed);
s.ptr.store(range.start, Ordering::Relaxed);
s.end.store(range.end, Ordering::Relaxed);
self.enable_irq();
self.start();
@ -154,16 +153,16 @@ impl<'d> Rng<'d> {
self.disable_irq();
// The interrupt is now disabled and can't preempt us anymore, so the order doesn't matter here.
STATE.ptr.store(ptr::null_mut(), Ordering::Relaxed);
STATE.end.store(ptr::null_mut(), Ordering::Relaxed);
s.ptr.store(ptr::null_mut(), Ordering::Relaxed);
s.end.store(ptr::null_mut(), Ordering::Relaxed);
});
poll_fn(|cx| {
STATE.waker.register(cx.waker());
s.waker.register(cx.waker());
// The interrupt will never modify `end`, so load it first and then get the most up-to-date `ptr`.
let end = STATE.end.load(Ordering::Relaxed);
let ptr = STATE.ptr.load(Ordering::Relaxed);
let end = s.end.load(Ordering::Relaxed);
let ptr = s.ptr.load(Ordering::Relaxed);
if ptr == end {
// We're done.
@ -183,7 +182,7 @@ impl<'d> Rng<'d> {
self.start();
for byte in dest.iter_mut() {
let regs = RNG::regs();
let regs = T::regs();
while regs.events_valrdy.read().bits() == 0 {}
regs.events_valrdy.reset();
*byte = regs.value.read().value().bits();
@ -193,13 +192,16 @@ impl<'d> Rng<'d> {
}
}
impl<'d> Drop for Rng<'d> {
impl<'d, T: Instance> Drop for Rng<'d, T> {
fn drop(&mut self) {
self.irq.disable()
self.stop();
let s = T::state();
s.ptr.store(ptr::null_mut(), Ordering::Relaxed);
s.end.store(ptr::null_mut(), Ordering::Relaxed);
}
}
impl<'d> rand_core::RngCore for Rng<'d> {
impl<'d, T: Instance> rand_core::RngCore for Rng<'d, T> {
fn fill_bytes(&mut self, dest: &mut [u8]) {
self.blocking_fill_bytes(dest);
}
@ -223,4 +225,53 @@ impl<'d> rand_core::RngCore for Rng<'d> {
}
}
impl<'d> rand_core::CryptoRng for Rng<'d> {}
impl<'d, T: Instance> rand_core::CryptoRng for Rng<'d, T> {}
pub(crate) mod sealed {
use super::*;
/// Peripheral static state
pub struct State {
pub ptr: AtomicPtr<u8>,
pub end: AtomicPtr<u8>,
pub waker: AtomicWaker,
}
impl State {
pub const fn new() -> Self {
Self {
ptr: AtomicPtr::new(ptr::null_mut()),
end: AtomicPtr::new(ptr::null_mut()),
waker: AtomicWaker::new(),
}
}
}
pub trait Instance {
fn regs() -> &'static crate::pac::rng::RegisterBlock;
fn state() -> &'static State;
}
}
/// RNG peripheral instance.
pub trait Instance: Peripheral<P = Self> + sealed::Instance + 'static + Send {
/// Interrupt for this peripheral.
type Interrupt: Interrupt;
}
macro_rules! impl_rng {
($type:ident, $pac_type:ident, $irq:ident) => {
impl crate::rng::sealed::Instance for peripherals::$type {
fn regs() -> &'static crate::pac::rng::RegisterBlock {
unsafe { &*pac::$pac_type::ptr() }
}
fn state() -> &'static crate::rng::sealed::State {
static STATE: crate::rng::sealed::State = crate::rng::sealed::State::new();
&STATE
}
}
impl crate::rng::Instance for peripherals::$type {
type Interrupt = crate::interrupt::$irq;
}
};
}

View File

@ -6,6 +6,7 @@ use core::future::poll_fn;
use core::sync::atomic::{compiler_fence, Ordering};
use core::task::Poll;
use embassy_cortex_m::interrupt::{Interrupt, InterruptExt};
use embassy_hal_common::drop::OnDrop;
use embassy_hal_common::{impl_peripheral, into_ref, PeripheralRef};
use embassy_sync::waitqueue::AtomicWaker;
@ -17,7 +18,6 @@ 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, Peripheral};
@ -28,9 +28,30 @@ use crate::{interrupt, pac, peripherals, Peripheral};
#[non_exhaustive]
pub enum Error {}
/// One-shot and continuous SAADC.
pub struct Saadc<'d, const N: usize> {
_p: PeripheralRef<'d, peripherals::SAADC>,
/// Interrupt handler.
pub struct InterruptHandler {
_private: (),
}
impl interrupt::Handler<interrupt::SAADC> for InterruptHandler {
unsafe fn on_interrupt() {
let r = unsafe { &*SAADC::ptr() };
if r.events_calibratedone.read().bits() != 0 {
r.intenclr.write(|w| w.calibratedone().clear());
WAKER.wake();
}
if r.events_end.read().bits() != 0 {
r.intenclr.write(|w| w.end().clear());
WAKER.wake();
}
if r.events_started.read().bits() != 0 {
r.intenclr.write(|w| w.started().clear());
WAKER.wake();
}
}
}
static WAKER: AtomicWaker = AtomicWaker::new();
@ -114,15 +135,20 @@ pub enum CallbackResult {
Stop,
}
/// One-shot and continuous SAADC.
pub struct Saadc<'d, const N: usize> {
_p: PeripheralRef<'d, peripherals::SAADC>,
}
impl<'d, const N: usize> Saadc<'d, N> {
/// Create a new SAADC driver.
pub fn new(
saadc: impl Peripheral<P = peripherals::SAADC> + 'd,
irq: impl Peripheral<P = interrupt::SAADC> + 'd,
_irq: impl interrupt::Binding<interrupt::SAADC, InterruptHandler> + 'd,
config: Config,
channel_configs: [ChannelConfig; N],
) -> Self {
into_ref!(saadc, irq);
into_ref!(saadc);
let r = unsafe { &*SAADC::ptr() };
@ -163,32 +189,12 @@ impl<'d, const N: usize> Saadc<'d, N> {
// Disable all events interrupts
r.intenclr.write(|w| unsafe { w.bits(0x003F_FFFF) });
irq.set_handler(Self::on_interrupt);
irq.unpend();
irq.enable();
unsafe { interrupt::SAADC::steal() }.unpend();
unsafe { interrupt::SAADC::steal() }.enable();
Self { _p: saadc }
}
fn on_interrupt(_ctx: *mut ()) {
let r = Self::regs();
if r.events_calibratedone.read().bits() != 0 {
r.intenclr.write(|w| w.calibratedone().clear());
WAKER.wake();
}
if r.events_end.read().bits() != 0 {
r.intenclr.write(|w| w.end().clear());
WAKER.wake();
}
if r.events_started.read().bits() != 0 {
r.intenclr.write(|w| w.started().clear());
WAKER.wake();
}
}
fn regs() -> &'static saadc::RegisterBlock {
unsafe { &*SAADC::ptr() }
}

View File

@ -3,6 +3,7 @@
#![macro_use]
use core::future::poll_fn;
use core::marker::PhantomData;
use core::sync::atomic::{compiler_fence, Ordering};
use core::task::Poll;
@ -14,7 +15,7 @@ pub use pac::spim0::frequency::FREQUENCY_A as Frequency;
use crate::chip::FORCE_COPY_BUFFER_SIZE;
use crate::gpio::sealed::Pin as _;
use crate::gpio::{self, AnyPin, Pin as GpioPin, PselBits};
use crate::interrupt::{Interrupt, InterruptExt};
use crate::interrupt::{self, Interrupt, InterruptExt};
use crate::util::{slice_in_ram_or, slice_ptr_parts, slice_ptr_parts_mut};
use crate::{pac, Peripheral};
@ -31,11 +32,6 @@ pub enum Error {
BufferNotInRAM,
}
/// SPIM driver.
pub struct Spim<'d, T: Instance> {
_p: PeripheralRef<'d, T>,
}
/// SPIM configuration.
#[non_exhaustive]
pub struct Config {
@ -62,11 +58,33 @@ impl Default for Config {
}
}
/// Interrupt handler.
pub struct InterruptHandler<T: Instance> {
_phantom: PhantomData<T>,
}
impl<T: Instance> interrupt::Handler<T::Interrupt> for InterruptHandler<T> {
unsafe fn on_interrupt() {
let r = T::regs();
let s = T::state();
if r.events_end.read().bits() != 0 {
s.end_waker.wake();
r.intenclr.write(|w| w.end().clear());
}
}
}
/// SPIM driver.
pub struct Spim<'d, T: Instance> {
_p: PeripheralRef<'d, T>,
}
impl<'d, T: Instance> Spim<'d, T> {
/// Create a new SPIM driver.
pub fn new(
spim: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
sck: impl Peripheral<P = impl GpioPin> + 'd,
miso: impl Peripheral<P = impl GpioPin> + 'd,
mosi: impl Peripheral<P = impl GpioPin> + 'd,
@ -75,7 +93,6 @@ impl<'d, T: Instance> Spim<'d, T> {
into_ref!(sck, miso, mosi);
Self::new_inner(
spim,
irq,
sck.map_into(),
Some(miso.map_into()),
Some(mosi.map_into()),
@ -86,36 +103,35 @@ impl<'d, T: Instance> Spim<'d, T> {
/// Create a new SPIM driver, capable of TX only (MOSI only).
pub fn new_txonly(
spim: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
sck: impl Peripheral<P = impl GpioPin> + 'd,
mosi: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Self {
into_ref!(sck, mosi);
Self::new_inner(spim, irq, sck.map_into(), None, Some(mosi.map_into()), config)
Self::new_inner(spim, sck.map_into(), None, Some(mosi.map_into()), config)
}
/// Create a new SPIM driver, capable of RX only (MISO only).
pub fn new_rxonly(
spim: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
sck: impl Peripheral<P = impl GpioPin> + 'd,
miso: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Self {
into_ref!(sck, miso);
Self::new_inner(spim, irq, sck.map_into(), Some(miso.map_into()), None, config)
Self::new_inner(spim, sck.map_into(), Some(miso.map_into()), None, config)
}
fn new_inner(
spim: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
sck: PeripheralRef<'d, AnyPin>,
miso: Option<PeripheralRef<'d, AnyPin>>,
mosi: Option<PeripheralRef<'d, AnyPin>>,
config: Config,
) -> Self {
into_ref!(spim, irq);
into_ref!(spim);
let r = T::regs();
@ -191,23 +207,12 @@ impl<'d, T: Instance> Spim<'d, T> {
// Disable all events interrupts
r.intenclr.write(|w| unsafe { w.bits(0xFFFF_FFFF) });
irq.set_handler(Self::on_interrupt);
irq.unpend();
irq.enable();
unsafe { T::Interrupt::steal() }.unpend();
unsafe { T::Interrupt::steal() }.enable();
Self { _p: spim }
}
fn on_interrupt(_: *mut ()) {
let r = T::regs();
let s = T::state();
if r.events_end.read().bits() != 0 {
s.end_waker.wake();
r.intenclr.write(|w| w.end().clear());
}
}
fn prepare(&mut self, rx: *mut [u8], tx: *const [u8]) -> Result<(), Error> {
slice_in_ram_or(tx, Error::BufferNotInRAM)?;
// NOTE: RAM slice check for rx is not necessary, as a mutable

View File

@ -2,6 +2,7 @@
#![macro_use]
use core::future::poll_fn;
use core::marker::PhantomData;
use core::sync::atomic::{compiler_fence, Ordering};
use core::task::Poll;
@ -12,7 +13,7 @@ pub use embedded_hal_02::spi::{Mode, Phase, Polarity, MODE_0, MODE_1, MODE_2, MO
use crate::chip::FORCE_COPY_BUFFER_SIZE;
use crate::gpio::sealed::Pin as _;
use crate::gpio::{self, AnyPin, Pin as GpioPin};
use crate::interrupt::{Interrupt, InterruptExt};
use crate::interrupt::{self, Interrupt, InterruptExt};
use crate::util::{slice_in_ram_or, slice_ptr_parts, slice_ptr_parts_mut};
use crate::{pac, Peripheral};
@ -29,11 +30,6 @@ pub enum Error {
BufferNotInRAM,
}
/// SPIS driver.
pub struct Spis<'d, T: Instance> {
_p: PeripheralRef<'d, T>,
}
/// SPIS configuration.
#[non_exhaustive]
pub struct Config {
@ -67,11 +63,38 @@ impl Default for Config {
}
}
/// Interrupt handler.
pub struct InterruptHandler<T: Instance> {
_phantom: PhantomData<T>,
}
impl<T: Instance> interrupt::Handler<T::Interrupt> for InterruptHandler<T> {
unsafe fn on_interrupt() {
let r = T::regs();
let s = T::state();
if r.events_end.read().bits() != 0 {
s.waker.wake();
r.intenclr.write(|w| w.end().clear());
}
if r.events_acquired.read().bits() != 0 {
s.waker.wake();
r.intenclr.write(|w| w.acquired().clear());
}
}
}
/// SPIS driver.
pub struct Spis<'d, T: Instance> {
_p: PeripheralRef<'d, T>,
}
impl<'d, T: Instance> Spis<'d, T> {
/// Create a new SPIS driver.
pub fn new(
spis: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
cs: impl Peripheral<P = impl GpioPin> + 'd,
sck: impl Peripheral<P = impl GpioPin> + 'd,
miso: impl Peripheral<P = impl GpioPin> + 'd,
@ -81,7 +104,6 @@ impl<'d, T: Instance> Spis<'d, T> {
into_ref!(cs, sck, miso, mosi);
Self::new_inner(
spis,
irq,
cs.map_into(),
sck.map_into(),
Some(miso.map_into()),
@ -93,48 +115,31 @@ impl<'d, T: Instance> Spis<'d, T> {
/// Create a new SPIS driver, capable of TX only (MISO only).
pub fn new_txonly(
spis: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
cs: impl Peripheral<P = impl GpioPin> + 'd,
sck: impl Peripheral<P = impl GpioPin> + 'd,
miso: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Self {
into_ref!(cs, sck, miso);
Self::new_inner(
spis,
irq,
cs.map_into(),
sck.map_into(),
Some(miso.map_into()),
None,
config,
)
Self::new_inner(spis, cs.map_into(), sck.map_into(), Some(miso.map_into()), None, config)
}
/// Create a new SPIS driver, capable of RX only (MOSI only).
pub fn new_rxonly(
spis: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
cs: impl Peripheral<P = impl GpioPin> + 'd,
sck: impl Peripheral<P = impl GpioPin> + 'd,
mosi: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Self {
into_ref!(cs, sck, mosi);
Self::new_inner(
spis,
irq,
cs.map_into(),
sck.map_into(),
None,
Some(mosi.map_into()),
config,
)
Self::new_inner(spis, cs.map_into(), sck.map_into(), None, Some(mosi.map_into()), config)
}
fn new_inner(
spis: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
cs: PeripheralRef<'d, AnyPin>,
sck: PeripheralRef<'d, AnyPin>,
miso: Option<PeripheralRef<'d, AnyPin>>,
@ -143,7 +148,7 @@ impl<'d, T: Instance> Spis<'d, T> {
) -> Self {
compiler_fence(Ordering::SeqCst);
into_ref!(spis, irq, cs, sck);
into_ref!(spis, cs, sck);
let r = T::regs();
@ -209,28 +214,12 @@ impl<'d, T: Instance> Spis<'d, T> {
// Disable all events interrupts.
r.intenclr.write(|w| unsafe { w.bits(0xFFFF_FFFF) });
irq.set_handler(Self::on_interrupt);
irq.unpend();
irq.enable();
unsafe { T::Interrupt::steal() }.unpend();
unsafe { T::Interrupt::steal() }.enable();
Self { _p: spis }
}
fn on_interrupt(_: *mut ()) {
let r = T::regs();
let s = T::state();
if r.events_end.read().bits() != 0 {
s.waker.wake();
r.intenclr.write(|w| w.end().clear());
}
if r.events_acquired.read().bits() != 0 {
s.waker.wake();
r.intenclr.write(|w| w.acquired().clear());
}
}
fn prepare(&mut self, rx: *mut [u8], tx: *const [u8]) -> Result<(), Error> {
slice_in_ram_or(tx, Error::BufferNotInRAM)?;
// NOTE: RAM slice check for rx is not necessary, as a mutable

View File

@ -3,6 +3,7 @@
use core::future::poll_fn;
use core::task::Poll;
use embassy_cortex_m::interrupt::Interrupt;
use embassy_hal_common::drop::OnDrop;
use embassy_hal_common::{into_ref, PeripheralRef};
use embassy_sync::waitqueue::AtomicWaker;
@ -12,27 +13,39 @@ use crate::interrupt::InterruptExt;
use crate::peripherals::TEMP;
use crate::{interrupt, pac, Peripheral};
/// Interrupt handler.
pub struct InterruptHandler {
_private: (),
}
impl interrupt::Handler<interrupt::TEMP> for InterruptHandler {
unsafe fn on_interrupt() {
let r = unsafe { &*pac::TEMP::PTR };
r.intenclr.write(|w| w.datardy().clear());
WAKER.wake();
}
}
/// Builtin temperature sensor driver.
pub struct Temp<'d> {
_irq: PeripheralRef<'d, interrupt::TEMP>,
_peri: PeripheralRef<'d, TEMP>,
}
static WAKER: AtomicWaker = AtomicWaker::new();
impl<'d> Temp<'d> {
/// Create a new temperature sensor driver.
pub fn new(_t: impl Peripheral<P = TEMP> + 'd, irq: impl Peripheral<P = interrupt::TEMP> + 'd) -> Self {
into_ref!(_t, irq);
pub fn new(
_peri: impl Peripheral<P = TEMP> + 'd,
_irq: impl interrupt::Binding<interrupt::TEMP, InterruptHandler> + 'd,
) -> Self {
into_ref!(_peri);
// Enable interrupt that signals temperature values
irq.disable();
irq.set_handler(|_| {
let t = Self::regs();
t.intenclr.write(|w| w.datardy().clear());
WAKER.wake();
});
irq.enable();
Self { _irq: irq }
unsafe { interrupt::TEMP::steal() }.unpend();
unsafe { interrupt::TEMP::steal() }.enable();
Self { _peri }
}
/// Perform an asynchronous temperature measurement. The returned future

View File

@ -6,15 +6,9 @@
#![macro_use]
use core::future::poll_fn;
use core::marker::PhantomData;
use core::task::Poll;
use embassy_hal_common::drop::OnDrop;
use embassy_hal_common::{into_ref, PeripheralRef};
use embassy_sync::waitqueue::AtomicWaker;
use crate::interrupt::{Interrupt, InterruptExt};
use crate::interrupt::Interrupt;
use crate::ppi::{Event, Task};
use crate::{pac, Peripheral};
@ -26,8 +20,6 @@ pub(crate) mod sealed {
/// The number of CC registers this instance has.
const CCS: usize;
fn regs() -> &'static pac::timer0::RegisterBlock;
/// Storage for the waker for CC register `n`.
fn waker(n: usize) -> &'static AtomicWaker;
}
pub trait ExtendedInstance {}
@ -50,12 +42,6 @@ macro_rules! impl_timer {
fn regs() -> &'static pac::timer0::RegisterBlock {
unsafe { &*(pac::$pac_type::ptr() as *const pac::timer0::RegisterBlock) }
}
fn waker(n: usize) -> &'static ::embassy_sync::waitqueue::AtomicWaker {
use ::embassy_sync::waitqueue::AtomicWaker;
const NEW_AW: AtomicWaker = AtomicWaker::new();
static WAKERS: [AtomicWaker; $ccs] = [NEW_AW; $ccs];
&WAKERS[n]
}
}
impl crate::timer::Instance for peripherals::$type {
type Interrupt = crate::interrupt::$irq;
@ -99,73 +85,49 @@ pub enum Frequency {
/// nRF Timer driver.
///
/// The timer has an internal counter, which is incremented for every tick of the timer.
/// The counter is 32-bit, so it wraps back to 0 at 4294967296.
/// The counter is 32-bit, so it wraps back to 0 when it reaches 2^32.
///
/// It has either 4 or 6 Capture/Compare registers, which can be used to capture the current state of the counter
/// or trigger an event when the counter reaches a certain value.
pub trait TimerType: sealed::TimerType {}
/// Marker type indicating the timer driver can await expiration (it owns the timer interrupt).
pub enum Awaitable {}
/// Marker type indicating the timer driver cannot await expiration (it does not own the timer interrupt).
pub enum NotAwaitable {}
impl sealed::TimerType for Awaitable {}
impl sealed::TimerType for NotAwaitable {}
impl TimerType for Awaitable {}
impl TimerType for NotAwaitable {}
/// Timer driver.
pub struct Timer<'d, T: Instance, I: TimerType = NotAwaitable> {
pub struct Timer<'d, T: Instance> {
_p: PeripheralRef<'d, T>,
_i: PhantomData<I>,
}
impl<'d, T: Instance> Timer<'d, T, Awaitable> {
/// Create a new async-capable timer driver.
pub fn new_awaitable(timer: impl Peripheral<P = T> + 'd, irq: impl Peripheral<P = T::Interrupt> + 'd) -> Self {
into_ref!(irq);
irq.set_handler(Self::on_interrupt);
irq.unpend();
irq.enable();
Self::new_inner(timer)
}
}
impl<'d, T: Instance> Timer<'d, T, NotAwaitable> {
/// Create a `Timer` driver without an interrupt, meaning `Cc::wait` won't work.
impl<'d, T: Instance> Timer<'d, T> {
/// Create a new `Timer` driver.
///
/// This can be useful for triggering tasks via PPI
/// `Uarte` uses this internally.
pub fn new(timer: impl Peripheral<P = T> + 'd) -> Self {
Self::new_inner(timer)
Self::new_inner(timer, false)
}
}
impl<'d, T: Instance, I: TimerType> Timer<'d, T, I> {
/// Create a `Timer` without an interrupt, meaning `Cc::wait` won't work.
/// Create a new `Timer` driver in counter mode.
///
/// This is used by the public constructors.
fn new_inner(timer: impl Peripheral<P = T> + 'd) -> Self {
/// This can be useful for triggering tasks via PPI
/// `Uarte` uses this internally.
pub fn new_counter(timer: impl Peripheral<P = T> + 'd) -> Self {
Self::new_inner(timer, true)
}
fn new_inner(timer: impl Peripheral<P = T> + 'd, is_counter: bool) -> Self {
into_ref!(timer);
let regs = T::regs();
let mut this = Self {
_p: timer,
_i: PhantomData,
};
let mut this = Self { _p: timer };
// Stop the timer before doing anything else,
// since changing BITMODE while running can cause 'unpredictable behaviour' according to the specification.
this.stop();
// Set the instance to timer mode.
regs.mode.write(|w| w.mode().timer());
if is_counter {
regs.mode.write(|w| w.mode().counter());
} else {
regs.mode.write(|w| w.mode().timer());
}
// Make the counter's max value as high as possible.
// TODO: is there a reason someone would want to set this lower?
@ -225,6 +187,14 @@ impl<'d, T: Instance, I: TimerType> Timer<'d, T, I> {
Task::from_reg(&T::regs().tasks_clear)
}
/// Returns the COUNT task, for use with PPI.
///
/// When triggered, this task increments the timer's counter by 1.
/// Only works in counter mode.
pub fn task_count(&self) -> Task {
Task::from_reg(&T::regs().tasks_count)
}
/// Change the timer's frequency.
///
/// This will stop the timer if it isn't already stopped,
@ -239,31 +209,17 @@ impl<'d, T: Instance, I: TimerType> Timer<'d, T, I> {
.write(|w| unsafe { w.prescaler().bits(frequency as u8) })
}
fn on_interrupt(_: *mut ()) {
let regs = T::regs();
for n in 0..T::CCS {
if regs.events_compare[n].read().bits() != 0 {
// Clear the interrupt, otherwise the interrupt will be repeatedly raised as soon as the interrupt handler exits.
// We can't clear the event, because it's used to poll whether the future is done or still pending.
regs.intenclr
.modify(|r, w| unsafe { w.bits(r.bits() | (1 << (16 + n))) });
T::waker(n).wake();
}
}
}
/// Returns this timer's `n`th CC register.
///
/// # Panics
/// Panics if `n` >= the number of CC registers this timer has (4 for a normal timer, 6 for an extended timer).
pub fn cc(&mut self, n: usize) -> Cc<T, I> {
pub fn cc(&mut self, n: usize) -> Cc<T> {
if n >= T::CCS {
panic!("Cannot get CC register {} of timer with {} CC registers.", n, T::CCS);
}
Cc {
n,
_p: self._p.reborrow(),
_i: PhantomData,
}
}
}
@ -275,49 +231,12 @@ 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<'d, T: Instance, I: TimerType = NotAwaitable> {
pub struct Cc<'d, T: Instance> {
n: usize,
_p: PeripheralRef<'d, T>,
_i: PhantomData<I>,
}
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`.
pub async fn wait(&mut self) {
let regs = T::regs();
// Enable the interrupt for this CC's COMPARE event.
regs.intenset
.modify(|r, w| unsafe { w.bits(r.bits() | (1 << (16 + self.n))) });
// Disable the interrupt if the future is dropped.
let on_drop = OnDrop::new(|| {
regs.intenclr
.modify(|r, w| unsafe { w.bits(r.bits() | (1 << (16 + self.n))) });
});
poll_fn(|cx| {
T::waker(self.n).register(cx.waker());
if regs.events_compare[self.n].read().bits() != 0 {
// Reset the register for next time
regs.events_compare[self.n].reset();
Poll::Ready(())
} else {
Poll::Pending
}
})
.await;
// The interrupt was already disabled in the interrupt handler, so there's no need to disable it again.
on_drop.defuse();
}
}
impl<'d, T: Instance> Cc<'d, T, NotAwaitable> {}
impl<'d, T: Instance, I: TimerType> Cc<'d, T, I> {
impl<'d, T: Instance> Cc<'d, T> {
/// Get the current value stored in the register.
pub fn read(&self) -> u32 {
T::regs().cc[self.n].read().cc().bits()

View File

@ -3,6 +3,7 @@
#![macro_use]
use core::future::{poll_fn, Future};
use core::marker::PhantomData;
use core::sync::atomic::compiler_fence;
use core::sync::atomic::Ordering::SeqCst;
use core::task::Poll;
@ -15,7 +16,7 @@ use embassy_time::{Duration, Instant};
use crate::chip::{EASY_DMA_SIZE, FORCE_COPY_BUFFER_SIZE};
use crate::gpio::Pin as GpioPin;
use crate::interrupt::{Interrupt, InterruptExt};
use crate::interrupt::{self, Interrupt, InterruptExt};
use crate::util::{slice_in_ram, slice_in_ram_or};
use crate::{gpio, pac, Peripheral};
@ -92,6 +93,27 @@ pub enum Error {
Timeout,
}
/// Interrupt handler.
pub struct InterruptHandler<T: Instance> {
_phantom: PhantomData<T>,
}
impl<T: Instance> interrupt::Handler<T::Interrupt> for InterruptHandler<T> {
unsafe fn on_interrupt() {
let r = T::regs();
let s = T::state();
if r.events_stopped.read().bits() != 0 {
s.end_waker.wake();
r.intenclr.write(|w| w.stopped().clear());
}
if r.events_error.read().bits() != 0 {
s.end_waker.wake();
r.intenclr.write(|w| w.error().clear());
}
}
}
/// TWI driver.
pub struct Twim<'d, T: Instance> {
_p: PeripheralRef<'d, T>,
@ -101,12 +123,12 @@ impl<'d, T: Instance> Twim<'d, T> {
/// Create a new TWI driver.
pub fn new(
twim: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
sda: impl Peripheral<P = impl GpioPin> + 'd,
scl: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Self {
into_ref!(twim, irq, sda, scl);
into_ref!(twim, sda, scl);
let r = T::regs();
@ -152,27 +174,12 @@ impl<'d, T: Instance> Twim<'d, T> {
// Disable all events interrupts
r.intenclr.write(|w| unsafe { w.bits(0xFFFF_FFFF) });
irq.set_handler(Self::on_interrupt);
irq.unpend();
irq.enable();
unsafe { T::Interrupt::steal() }.unpend();
unsafe { T::Interrupt::steal() }.enable();
Self { _p: twim }
}
fn on_interrupt(_: *mut ()) {
let r = T::regs();
let s = T::state();
if r.events_stopped.read().bits() != 0 {
s.end_waker.wake();
r.intenclr.write(|w| w.stopped().clear());
}
if r.events_error.read().bits() != 0 {
s.end_waker.wake();
r.intenclr.write(|w| w.error().clear());
}
}
/// Set TX buffer, checking that it is in RAM and has suitable length.
unsafe fn set_tx_buffer(&mut self, buffer: &[u8]) -> Result<(), Error> {
slice_in_ram_or(buffer, Error::BufferNotInRAM)?;

View File

@ -3,6 +3,7 @@
#![macro_use]
use core::future::{poll_fn, Future};
use core::marker::PhantomData;
use core::sync::atomic::compiler_fence;
use core::sync::atomic::Ordering::SeqCst;
use core::task::Poll;
@ -14,7 +15,7 @@ use embassy_time::{Duration, Instant};
use crate::chip::{EASY_DMA_SIZE, FORCE_COPY_BUFFER_SIZE};
use crate::gpio::Pin as GpioPin;
use crate::interrupt::{Interrupt, InterruptExt};
use crate::interrupt::{self, Interrupt, InterruptExt};
use crate::util::slice_in_ram_or;
use crate::{gpio, pac, Peripheral};
@ -108,6 +109,31 @@ pub enum Command {
Write(usize),
}
/// Interrupt handler.
pub struct InterruptHandler<T: Instance> {
_phantom: PhantomData<T>,
}
impl<T: Instance> interrupt::Handler<T::Interrupt> for InterruptHandler<T> {
unsafe fn on_interrupt() {
let r = T::regs();
let s = T::state();
if r.events_read.read().bits() != 0 || r.events_write.read().bits() != 0 {
s.waker.wake();
r.intenclr.modify(|_r, w| w.read().clear().write().clear());
}
if r.events_stopped.read().bits() != 0 {
s.waker.wake();
r.intenclr.modify(|_r, w| w.stopped().clear());
}
if r.events_error.read().bits() != 0 {
s.waker.wake();
r.intenclr.modify(|_r, w| w.error().clear());
}
}
}
/// TWIS driver.
pub struct Twis<'d, T: Instance> {
_p: PeripheralRef<'d, T>,
@ -117,12 +143,12 @@ impl<'d, T: Instance> Twis<'d, T> {
/// Create a new TWIS driver.
pub fn new(
twis: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
sda: impl Peripheral<P = impl GpioPin> + 'd,
scl: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Self {
into_ref!(twis, irq, sda, scl);
into_ref!(twis, sda, scl);
let r = T::regs();
@ -178,31 +204,12 @@ impl<'d, T: Instance> Twis<'d, T> {
// Generate suspend on read event
r.shorts.write(|w| w.read_suspend().enabled());
irq.set_handler(Self::on_interrupt);
irq.unpend();
irq.enable();
unsafe { T::Interrupt::steal() }.unpend();
unsafe { T::Interrupt::steal() }.enable();
Self { _p: twis }
}
fn on_interrupt(_: *mut ()) {
let r = T::regs();
let s = T::state();
if r.events_read.read().bits() != 0 || r.events_write.read().bits() != 0 {
s.waker.wake();
r.intenclr.modify(|_r, w| w.read().clear().write().clear());
}
if r.events_stopped.read().bits() != 0 {
s.waker.wake();
r.intenclr.modify(|_r, w| w.stopped().clear());
}
if r.events_error.read().bits() != 0 {
s.waker.wake();
r.intenclr.modify(|_r, w| w.error().clear());
}
}
/// Set TX buffer, checking that it is in RAM and has suitable length.
unsafe fn set_tx_buffer(&mut self, buffer: &[u8]) -> Result<(), Error> {
slice_in_ram_or(buffer, Error::BufferNotInRAM)?;

View File

@ -14,6 +14,7 @@
#![macro_use]
use core::future::poll_fn;
use core::marker::PhantomData;
use core::sync::atomic::{compiler_fence, Ordering};
use core::task::Poll;
@ -26,7 +27,7 @@ pub use pac::uarte0::{baudrate::BAUDRATE_A as Baudrate, config::PARITY_A as Pari
use crate::chip::{EASY_DMA_SIZE, FORCE_COPY_BUFFER_SIZE};
use crate::gpio::sealed::Pin as _;
use crate::gpio::{self, AnyPin, Pin as GpioPin, PselBits};
use crate::interrupt::{Interrupt, InterruptExt};
use crate::interrupt::{self, 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;
@ -62,6 +63,27 @@ pub enum Error {
BufferNotInRAM,
}
/// Interrupt handler.
pub struct InterruptHandler<T: Instance> {
_phantom: PhantomData<T>,
}
impl<T: Instance> interrupt::Handler<T::Interrupt> for InterruptHandler<T> {
unsafe fn on_interrupt() {
let r = T::regs();
let s = T::state();
if r.events_endrx.read().bits() != 0 {
s.endrx_waker.wake();
r.intenclr.write(|w| w.endrx().clear());
}
if r.events_endtx.read().bits() != 0 {
s.endtx_waker.wake();
r.intenclr.write(|w| w.endtx().clear());
}
}
}
/// UARTE driver.
pub struct Uarte<'d, T: Instance> {
tx: UarteTx<'d, T>,
@ -86,19 +108,19 @@ impl<'d, T: Instance> Uarte<'d, T> {
/// Create a new UARTE without hardware flow control
pub fn new(
uarte: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
rxd: impl Peripheral<P = impl GpioPin> + 'd,
txd: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Self {
into_ref!(rxd, txd);
Self::new_inner(uarte, irq, rxd.map_into(), txd.map_into(), None, None, config)
Self::new_inner(uarte, 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 Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
rxd: impl Peripheral<P = impl GpioPin> + 'd,
txd: impl Peripheral<P = impl GpioPin> + 'd,
cts: impl Peripheral<P = impl GpioPin> + 'd,
@ -108,7 +130,6 @@ impl<'d, T: Instance> Uarte<'d, T> {
into_ref!(rxd, txd, cts, rts);
Self::new_inner(
uarte,
irq,
rxd.map_into(),
txd.map_into(),
Some(cts.map_into()),
@ -119,14 +140,13 @@ impl<'d, T: Instance> Uarte<'d, T> {
fn new_inner(
uarte: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
rxd: PeripheralRef<'d, AnyPin>,
txd: PeripheralRef<'d, AnyPin>,
cts: Option<PeripheralRef<'d, AnyPin>>,
rts: Option<PeripheralRef<'d, AnyPin>>,
config: Config,
) -> Self {
into_ref!(uarte, irq);
into_ref!(uarte);
let r = T::regs();
@ -148,9 +168,8 @@ impl<'d, T: Instance> Uarte<'d, T> {
}
r.psel.rts.write(|w| unsafe { w.bits(rts.psel_bits()) });
irq.set_handler(Self::on_interrupt);
irq.unpend();
irq.enable();
unsafe { T::Interrupt::steal() }.unpend();
unsafe { T::Interrupt::steal() }.enable();
let hardware_flow_control = match (rts.is_some(), cts.is_some()) {
(false, false) => false,
@ -238,20 +257,6 @@ impl<'d, T: Instance> Uarte<'d, T> {
Event::from_reg(&r.events_endtx)
}
fn on_interrupt(_: *mut ()) {
let r = T::regs();
let s = T::state();
if r.events_endrx.read().bits() != 0 {
s.endrx_waker.wake();
r.intenclr.write(|w| w.endrx().clear());
}
if r.events_endtx.read().bits() != 0 {
s.endtx_waker.wake();
r.intenclr.write(|w| w.endtx().clear());
}
}
/// Read bytes until the buffer is filled.
pub async fn read(&mut self, buffer: &mut [u8]) -> Result<(), Error> {
self.rx.read(buffer).await
@ -308,34 +313,33 @@ impl<'d, T: Instance> UarteTx<'d, T> {
/// Create a new tx-only UARTE without hardware flow control
pub fn new(
uarte: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
txd: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Self {
into_ref!(txd);
Self::new_inner(uarte, irq, txd.map_into(), None, config)
Self::new_inner(uarte, txd.map_into(), None, config)
}
/// Create a new tx-only UARTE with hardware flow control (RTS/CTS)
pub fn new_with_rtscts(
uarte: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
txd: impl Peripheral<P = impl GpioPin> + 'd,
cts: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Self {
into_ref!(txd, cts);
Self::new_inner(uarte, irq, txd.map_into(), Some(cts.map_into()), config)
Self::new_inner(uarte, txd.map_into(), Some(cts.map_into()), config)
}
fn new_inner(
uarte: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
txd: PeripheralRef<'d, AnyPin>,
cts: Option<PeripheralRef<'d, AnyPin>>,
config: Config,
) -> Self {
into_ref!(uarte, irq);
into_ref!(uarte);
let r = T::regs();
@ -354,9 +358,8 @@ impl<'d, T: Instance> UarteTx<'d, T> {
let hardware_flow_control = cts.is_some();
configure(r, config, hardware_flow_control);
irq.set_handler(Uarte::<T>::on_interrupt);
irq.unpend();
irq.enable();
unsafe { T::Interrupt::steal() }.unpend();
unsafe { T::Interrupt::steal() }.enable();
let s = T::state();
s.tx_rx_refcount.store(1, Ordering::Relaxed);
@ -506,34 +509,33 @@ impl<'d, T: Instance> UarteRx<'d, T> {
/// Create a new rx-only UARTE without hardware flow control
pub fn new(
uarte: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
rxd: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Self {
into_ref!(rxd);
Self::new_inner(uarte, irq, rxd.map_into(), None, config)
Self::new_inner(uarte, rxd.map_into(), None, config)
}
/// Create a new rx-only UARTE with hardware flow control (RTS/CTS)
pub fn new_with_rtscts(
uarte: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
rxd: impl Peripheral<P = impl GpioPin> + 'd,
rts: impl Peripheral<P = impl GpioPin> + 'd,
config: Config,
) -> Self {
into_ref!(rxd, rts);
Self::new_inner(uarte, irq, rxd.map_into(), Some(rts.map_into()), config)
Self::new_inner(uarte, rxd.map_into(), Some(rts.map_into()), config)
}
fn new_inner(
uarte: impl Peripheral<P = T> + 'd,
irq: impl Peripheral<P = T::Interrupt> + 'd,
rxd: PeripheralRef<'d, AnyPin>,
rts: Option<PeripheralRef<'d, AnyPin>>,
config: Config,
) -> Self {
into_ref!(uarte, irq);
into_ref!(uarte);
let r = T::regs();
@ -549,9 +551,8 @@ impl<'d, T: Instance> UarteRx<'d, T> {
r.psel.txd.write(|w| w.connect().disconnected());
r.psel.cts.write(|w| w.connect().disconnected());
irq.set_handler(Uarte::<T>::on_interrupt);
irq.unpend();
irq.enable();
unsafe { T::Interrupt::steal() }.unpend();
unsafe { T::Interrupt::steal() }.enable();
let hardware_flow_control = rts.is_some();
configure(r, config, hardware_flow_control);
@ -883,6 +884,7 @@ pub(crate) mod sealed {
pub trait Instance {
fn regs() -> &'static pac::uarte0::RegisterBlock;
fn state() -> &'static State;
fn buffered_state() -> &'static crate::buffered_uarte::State;
}
}
@ -902,6 +904,10 @@ macro_rules! impl_uarte {
static STATE: crate::uarte::sealed::State = crate::uarte::sealed::State::new();
&STATE
}
fn buffered_state() -> &'static crate::buffered_uarte::State {
static STATE: crate::buffered_uarte::State = crate::buffered_uarte::State::new();
&STATE
}
}
impl crate::uarte::Instance for peripherals::$type {
type Interrupt = crate::interrupt::$irq;

View File

@ -2,10 +2,12 @@
#![macro_use]
pub mod vbus_detect;
use core::future::poll_fn;
use core::marker::PhantomData;
use core::mem::MaybeUninit;
use core::sync::atomic::{compiler_fence, AtomicBool, AtomicU32, Ordering};
use core::sync::atomic::{compiler_fence, AtomicU32, Ordering};
use core::task::Poll;
use cortex_m::peripheral::NVIC;
@ -15,7 +17,8 @@ use embassy_usb_driver as driver;
use embassy_usb_driver::{Direction, EndpointAddress, EndpointError, EndpointInfo, EndpointType, Event, Unsupported};
use pac::usbd::RegisterBlock;
use crate::interrupt::{Interrupt, InterruptExt};
use self::vbus_detect::VbusDetect;
use crate::interrupt::{self, Interrupt, InterruptExt};
use crate::util::slice_in_ram;
use crate::{pac, Peripheral};
@ -26,185 +29,13 @@ static EP_IN_WAKERS: [AtomicWaker; 8] = [NEW_AW; 8];
static EP_OUT_WAKERS: [AtomicWaker; 8] = [NEW_AW; 8];
static READY_ENDPOINTS: AtomicU32 = AtomicU32::new(0);
/// Trait for detecting USB VBUS power.
///
/// There are multiple ways to detect USB power. The behavior
/// here provides a hook into determining whether it is.
pub trait VbusDetect {
/// Report whether power is detected.
///
/// This is indicated by the `USBREGSTATUS.VBUSDETECT` register, or the
/// `USBDETECTED`, `USBREMOVED` events from the `POWER` peripheral.
fn is_usb_detected(&self) -> bool;
/// Wait until USB power is ready.
///
/// USB power ready is indicated by the `USBREGSTATUS.OUTPUTRDY` register, or the
/// `USBPWRRDY` event from the `POWER` peripheral.
async fn wait_power_ready(&mut self) -> Result<(), ()>;
/// Interrupt handler.
pub struct InterruptHandler<T: Instance> {
_phantom: PhantomData<T>,
}
/// [`VbusDetect`] implementation using the native hardware POWER peripheral.
///
/// Unsuitable for usage with the nRF softdevice, since it reserves exclusive acces
/// to POWER. In that case, use [`VbusDetectSignal`].
#[cfg(not(feature = "_nrf5340-app"))]
pub struct HardwareVbusDetect {
_private: (),
}
static POWER_WAKER: AtomicWaker = NEW_AW;
#[cfg(not(feature = "_nrf5340-app"))]
impl HardwareVbusDetect {
/// Create a new `VbusDetectNative`.
pub fn new(power_irq: impl Interrupt) -> Self {
let regs = unsafe { &*pac::POWER::ptr() };
power_irq.set_handler(Self::on_interrupt);
power_irq.unpend();
power_irq.enable();
regs.intenset
.write(|w| w.usbdetected().set().usbremoved().set().usbpwrrdy().set());
Self { _private: () }
}
#[cfg(not(feature = "_nrf5340-app"))]
fn on_interrupt(_: *mut ()) {
let regs = unsafe { &*pac::POWER::ptr() };
if regs.events_usbdetected.read().bits() != 0 {
regs.events_usbdetected.reset();
BUS_WAKER.wake();
}
if regs.events_usbremoved.read().bits() != 0 {
regs.events_usbremoved.reset();
BUS_WAKER.wake();
POWER_WAKER.wake();
}
if regs.events_usbpwrrdy.read().bits() != 0 {
regs.events_usbpwrrdy.reset();
POWER_WAKER.wake();
}
}
}
#[cfg(not(feature = "_nrf5340-app"))]
impl VbusDetect for HardwareVbusDetect {
fn is_usb_detected(&self) -> bool {
let regs = unsafe { &*pac::POWER::ptr() };
regs.usbregstatus.read().vbusdetect().is_vbus_present()
}
async fn wait_power_ready(&mut self) -> Result<(), ()> {
poll_fn(move |cx| {
POWER_WAKER.register(cx.waker());
let regs = unsafe { &*pac::POWER::ptr() };
if regs.usbregstatus.read().outputrdy().is_ready() {
Poll::Ready(Ok(()))
} else if !self.is_usb_detected() {
Poll::Ready(Err(()))
} else {
Poll::Pending
}
})
.await
}
}
/// Software-backed [`VbusDetect`] implementation.
///
/// This implementation does not interact with the hardware, it allows user code
/// to notify the power events by calling functions instead.
///
/// This is suitable for use with the nRF softdevice, by calling the functions
/// when the softdevice reports power-related events.
pub struct SoftwareVbusDetect {
usb_detected: AtomicBool,
power_ready: AtomicBool,
}
impl SoftwareVbusDetect {
/// Create a new `SoftwareVbusDetect`.
pub fn new(usb_detected: bool, power_ready: bool) -> Self {
BUS_WAKER.wake();
Self {
usb_detected: AtomicBool::new(usb_detected),
power_ready: AtomicBool::new(power_ready),
}
}
/// Report whether power was detected.
///
/// Equivalent to the `USBDETECTED`, `USBREMOVED` events from the `POWER` peripheral.
pub fn detected(&self, detected: bool) {
self.usb_detected.store(detected, Ordering::Relaxed);
self.power_ready.store(false, Ordering::Relaxed);
BUS_WAKER.wake();
POWER_WAKER.wake();
}
/// Report when USB power is ready.
///
/// Equivalent to the `USBPWRRDY` event from the `POWER` peripheral.
pub fn ready(&self) {
self.power_ready.store(true, Ordering::Relaxed);
POWER_WAKER.wake();
}
}
impl VbusDetect for &SoftwareVbusDetect {
fn is_usb_detected(&self) -> bool {
self.usb_detected.load(Ordering::Relaxed)
}
async fn wait_power_ready(&mut self) -> Result<(), ()> {
poll_fn(move |cx| {
POWER_WAKER.register(cx.waker());
if self.power_ready.load(Ordering::Relaxed) {
Poll::Ready(Ok(()))
} else if !self.usb_detected.load(Ordering::Relaxed) {
Poll::Ready(Err(()))
} else {
Poll::Pending
}
})
.await
}
}
/// USB driver.
pub struct Driver<'d, T: Instance, P: VbusDetect> {
_p: PeripheralRef<'d, T>,
alloc_in: Allocator,
alloc_out: Allocator,
usb_supply: P,
}
impl<'d, T: Instance, P: VbusDetect> Driver<'d, T, P> {
/// Create a new USB driver.
pub fn new(usb: impl Peripheral<P = T> + 'd, irq: impl Peripheral<P = T::Interrupt> + 'd, usb_supply: P) -> Self {
into_ref!(usb, irq);
irq.set_handler(Self::on_interrupt);
irq.unpend();
irq.enable();
Self {
_p: usb,
alloc_in: Allocator::new(),
alloc_out: Allocator::new(),
usb_supply,
}
}
fn on_interrupt(_: *mut ()) {
impl<T: Instance> interrupt::Handler<T::Interrupt> for InterruptHandler<T> {
unsafe fn on_interrupt() {
let regs = T::regs();
if regs.events_usbreset.read().bits() != 0 {
@ -255,11 +86,40 @@ impl<'d, T: Instance, P: VbusDetect> Driver<'d, T, P> {
}
}
impl<'d, T: Instance, P: VbusDetect + 'd> driver::Driver<'d> for Driver<'d, T, P> {
/// USB driver.
pub struct Driver<'d, T: Instance, V: VbusDetect> {
_p: PeripheralRef<'d, T>,
alloc_in: Allocator,
alloc_out: Allocator,
vbus_detect: V,
}
impl<'d, T: Instance, V: VbusDetect> Driver<'d, T, V> {
/// Create a new USB driver.
pub fn new(
usb: impl Peripheral<P = T> + 'd,
_irq: impl interrupt::Binding<T::Interrupt, InterruptHandler<T>> + 'd,
vbus_detect: V,
) -> Self {
into_ref!(usb);
unsafe { T::Interrupt::steal() }.unpend();
unsafe { T::Interrupt::steal() }.enable();
Self {
_p: usb,
alloc_in: Allocator::new(),
alloc_out: Allocator::new(),
vbus_detect,
}
}
}
impl<'d, T: Instance, V: VbusDetect + 'd> driver::Driver<'d> for Driver<'d, T, V> {
type EndpointOut = Endpoint<'d, T, Out>;
type EndpointIn = Endpoint<'d, T, In>;
type ControlPipe = ControlPipe<'d, T>;
type Bus = Bus<'d, T, P>;
type Bus = Bus<'d, T, V>;
fn alloc_endpoint_in(
&mut self,
@ -298,7 +158,7 @@ impl<'d, T: Instance, P: VbusDetect + 'd> driver::Driver<'d> for Driver<'d, T, P
Bus {
_p: unsafe { self._p.clone_unchecked() },
power_available: false,
usb_supply: self.usb_supply,
vbus_detect: self.vbus_detect,
},
ControlPipe {
_p: self._p,
@ -309,13 +169,13 @@ impl<'d, T: Instance, P: VbusDetect + 'd> driver::Driver<'d> for Driver<'d, T, P
}
/// USB bus.
pub struct Bus<'d, T: Instance, P: VbusDetect> {
pub struct Bus<'d, T: Instance, V: VbusDetect> {
_p: PeripheralRef<'d, T>,
power_available: bool,
usb_supply: P,
vbus_detect: V,
}
impl<'d, T: Instance, P: VbusDetect> driver::Bus for Bus<'d, T, P> {
impl<'d, T: Instance, V: VbusDetect> driver::Bus for Bus<'d, T, V> {
async fn enable(&mut self) {
let regs = T::regs();
@ -347,7 +207,7 @@ impl<'d, T: Instance, P: VbusDetect> driver::Bus for Bus<'d, T, P> {
w
});
if self.usb_supply.wait_power_ready().await.is_ok() {
if self.vbus_detect.wait_power_ready().await.is_ok() {
// Enable the USB pullup, allowing enumeration.
regs.usbpullup.write(|w| w.connect().enabled());
trace!("enabled");
@ -406,7 +266,7 @@ impl<'d, T: Instance, P: VbusDetect> driver::Bus for Bus<'d, T, P> {
trace!("USB event: ready");
}
if self.usb_supply.is_usb_detected() != self.power_available {
if self.vbus_detect.is_usb_detected() != self.power_available {
self.power_available = !self.power_available;
if self.power_available {
trace!("Power event: available");

View File

@ -0,0 +1,177 @@
//! Trait and implementations for performing VBUS detection.
use core::future::poll_fn;
use core::sync::atomic::{AtomicBool, Ordering};
use core::task::Poll;
use embassy_sync::waitqueue::AtomicWaker;
use super::BUS_WAKER;
use crate::interrupt::{self, Interrupt, InterruptExt};
use crate::pac;
/// Trait for detecting USB VBUS power.
///
/// There are multiple ways to detect USB power. The behavior
/// here provides a hook into determining whether it is.
pub trait VbusDetect {
/// Report whether power is detected.
///
/// This is indicated by the `USBREGSTATUS.VBUSDETECT` register, or the
/// `USBDETECTED`, `USBREMOVED` events from the `POWER` peripheral.
fn is_usb_detected(&self) -> bool;
/// Wait until USB power is ready.
///
/// USB power ready is indicated by the `USBREGSTATUS.OUTPUTRDY` register, or the
/// `USBPWRRDY` event from the `POWER` peripheral.
async fn wait_power_ready(&mut self) -> Result<(), ()>;
}
#[cfg(not(feature = "_nrf5340"))]
type UsbRegIrq = interrupt::POWER_CLOCK;
#[cfg(feature = "_nrf5340")]
type UsbRegIrq = interrupt::USBREGULATOR;
#[cfg(not(feature = "_nrf5340"))]
type UsbRegPeri = pac::POWER;
#[cfg(feature = "_nrf5340")]
type UsbRegPeri = pac::USBREGULATOR;
/// Interrupt handler.
pub struct InterruptHandler {
_private: (),
}
impl interrupt::Handler<UsbRegIrq> for InterruptHandler {
unsafe fn on_interrupt() {
let regs = unsafe { &*UsbRegPeri::ptr() };
if regs.events_usbdetected.read().bits() != 0 {
regs.events_usbdetected.reset();
BUS_WAKER.wake();
}
if regs.events_usbremoved.read().bits() != 0 {
regs.events_usbremoved.reset();
BUS_WAKER.wake();
POWER_WAKER.wake();
}
if regs.events_usbpwrrdy.read().bits() != 0 {
regs.events_usbpwrrdy.reset();
POWER_WAKER.wake();
}
}
}
/// [`VbusDetect`] implementation using the native hardware POWER peripheral.
///
/// Unsuitable for usage with the nRF softdevice, since it reserves exclusive acces
/// to POWER. In that case, use [`VbusDetectSignal`].
pub struct HardwareVbusDetect {
_private: (),
}
static POWER_WAKER: AtomicWaker = AtomicWaker::new();
impl HardwareVbusDetect {
/// Create a new `VbusDetectNative`.
pub fn new(_irq: impl interrupt::Binding<UsbRegIrq, InterruptHandler> + 'static) -> Self {
let regs = unsafe { &*UsbRegPeri::ptr() };
unsafe { UsbRegIrq::steal() }.unpend();
unsafe { UsbRegIrq::steal() }.enable();
regs.intenset
.write(|w| w.usbdetected().set().usbremoved().set().usbpwrrdy().set());
Self { _private: () }
}
}
impl VbusDetect for HardwareVbusDetect {
fn is_usb_detected(&self) -> bool {
let regs = unsafe { &*UsbRegPeri::ptr() };
regs.usbregstatus.read().vbusdetect().is_vbus_present()
}
async fn wait_power_ready(&mut self) -> Result<(), ()> {
poll_fn(move |cx| {
POWER_WAKER.register(cx.waker());
let regs = unsafe { &*UsbRegPeri::ptr() };
if regs.usbregstatus.read().outputrdy().is_ready() {
Poll::Ready(Ok(()))
} else if !self.is_usb_detected() {
Poll::Ready(Err(()))
} else {
Poll::Pending
}
})
.await
}
}
/// Software-backed [`VbusDetect`] implementation.
///
/// This implementation does not interact with the hardware, it allows user code
/// to notify the power events by calling functions instead.
///
/// This is suitable for use with the nRF softdevice, by calling the functions
/// when the softdevice reports power-related events.
pub struct SoftwareVbusDetect {
usb_detected: AtomicBool,
power_ready: AtomicBool,
}
impl SoftwareVbusDetect {
/// Create a new `SoftwareVbusDetect`.
pub fn new(usb_detected: bool, power_ready: bool) -> Self {
BUS_WAKER.wake();
Self {
usb_detected: AtomicBool::new(usb_detected),
power_ready: AtomicBool::new(power_ready),
}
}
/// Report whether power was detected.
///
/// Equivalent to the `USBDETECTED`, `USBREMOVED` events from the `POWER` peripheral.
pub fn detected(&self, detected: bool) {
self.usb_detected.store(detected, Ordering::Relaxed);
self.power_ready.store(false, Ordering::Relaxed);
BUS_WAKER.wake();
POWER_WAKER.wake();
}
/// Report when USB power is ready.
///
/// Equivalent to the `USBPWRRDY` event from the `POWER` peripheral.
pub fn ready(&self) {
self.power_ready.store(true, Ordering::Relaxed);
POWER_WAKER.wake();
}
}
impl VbusDetect for &SoftwareVbusDetect {
fn is_usb_detected(&self) -> bool {
self.usb_detected.load(Ordering::Relaxed)
}
async fn wait_power_ready(&mut self) -> Result<(), ()> {
poll_fn(move |cx| {
POWER_WAKER.register(cx.waker());
if self.power_ready.load(Ordering::Relaxed) {
Poll::Ready(Ok(()))
} else if !self.usb_detected.load(Ordering::Relaxed) {
Poll::Ready(Err(()))
} else {
Poll::Pending
}
})
.await
}
}