From 04944b6379814560a1d3732ed76b56751023f055 Mon Sep 17 00:00:00 2001 From: xoviat Date: Mon, 28 Dec 2020 20:48:26 -0600 Subject: [PATCH] overhaul implementation --- embassy-stm32f4/Cargo.toml | 1 + embassy-stm32f4/src/interrupt.rs | 129 ------ embassy-stm32f4/src/lib.rs | 2 +- embassy-stm32f4/src/uarte.rs | 758 ++++++++++--------------------- 4 files changed, 250 insertions(+), 640 deletions(-) delete mode 100644 embassy-stm32f4/src/interrupt.rs diff --git a/embassy-stm32f4/Cargo.toml b/embassy-stm32f4/Cargo.toml index fe2d1eadc..654ea69a6 100644 --- a/embassy-stm32f4/Cargo.toml +++ b/embassy-stm32f4/Cargo.toml @@ -39,4 +39,5 @@ log = { version = "0.4.11", optional = true } cortex-m-rt = "0.6.13" cortex-m = { version = "0.6.4" } embedded-hal = { version = "0.2.4" } +embedded-dma = { version = "0.1.2" } stm32f4xx-hal = { version = "0.8.3", features = ["rt"], git = "https://github.com/stm32-rs/stm32f4xx-hal.git" } diff --git a/embassy-stm32f4/src/interrupt.rs b/embassy-stm32f4/src/interrupt.rs deleted file mode 100644 index 17fc9ab34..000000000 --- a/embassy-stm32f4/src/interrupt.rs +++ /dev/null @@ -1,129 +0,0 @@ -//! Interrupt management -//! -//! This module implements an API for managing interrupts compatible with -//! nrf_softdevice::interrupt. Intended for switching between the two at compile-time. - -use core::sync::atomic::{compiler_fence, Ordering}; - -use crate::pac::{NVIC, NVIC_PRIO_BITS}; - -// Re-exports -pub use crate::pac::Interrupt; -pub use crate::pac::Interrupt::*; // needed for cortex-m-rt #[interrupt] -pub use cortex_m::interrupt::{CriticalSection, Mutex}; - -#[derive(Debug, Copy, Clone, Eq, PartialEq, Ord, PartialOrd)] -#[cfg_attr(feature = "defmt", derive(defmt::Format))] -#[repr(u8)] -pub enum Priority { - Level0 = 0, - Level1 = 1, - Level2 = 2, - Level3 = 3, - Level4 = 4, - Level5 = 5, - Level6 = 6, - Level7 = 7, -} - -impl Priority { - #[inline] - fn to_nvic(self) -> u8 { - (self as u8) << (8 - NVIC_PRIO_BITS) - } - - #[inline] - fn from_nvic(priority: u8) -> Self { - match priority >> (8 - NVIC_PRIO_BITS) { - 0 => Self::Level0, - 1 => Self::Level1, - 2 => Self::Level2, - 3 => Self::Level3, - 4 => Self::Level4, - 5 => Self::Level5, - 6 => Self::Level6, - 7 => Self::Level7, - _ => unreachable!(), - } - } -} - -#[inline] -pub fn free(f: F) -> R -where - F: FnOnce(&CriticalSection) -> R, -{ - unsafe { - // TODO: assert that we're in privileged level - // Needed because disabling irqs in non-privileged level is a noop, which would break safety. - - let primask: u32; - asm!("mrs {}, PRIMASK", out(reg) primask); - - asm!("cpsid i"); - - // Prevent compiler from reordering operations inside/outside the critical section. - compiler_fence(Ordering::SeqCst); - - let r = f(&CriticalSection::new()); - - compiler_fence(Ordering::SeqCst); - - if primask & 1 == 0 { - asm!("cpsie i"); - } - - r - } -} - -#[inline] -pub fn enable(irq: Interrupt) { - unsafe { - NVIC::unmask(irq); - } -} - -#[inline] -pub fn disable(irq: Interrupt) { - NVIC::mask(irq); -} - -#[inline] -pub fn is_active(irq: Interrupt) -> bool { - NVIC::is_active(irq) -} - -#[inline] -pub fn is_enabled(irq: Interrupt) -> bool { - NVIC::is_enabled(irq) -} - -#[inline] -pub fn is_pending(irq: Interrupt) -> bool { - NVIC::is_pending(irq) -} - -#[inline] -pub fn pend(irq: Interrupt) { - NVIC::pend(irq) -} - -#[inline] -pub fn unpend(irq: Interrupt) { - NVIC::unpend(irq) -} - -#[inline] -pub fn get_priority(irq: Interrupt) -> Priority { - Priority::from_nvic(NVIC::get_priority(irq)) -} - -#[inline] -pub fn set_priority(irq: Interrupt, prio: Priority) { - unsafe { - cortex_m::peripheral::Peripherals::steal() - .NVIC - .set_priority(irq, prio.to_nvic()) - } -} diff --git a/embassy-stm32f4/src/lib.rs b/embassy-stm32f4/src/lib.rs index f2304c94f..40386085a 100644 --- a/embassy-stm32f4/src/lib.rs +++ b/embassy-stm32f4/src/lib.rs @@ -331,6 +331,7 @@ pub use stm32f4xx_hal::stm32 as pac; macro_rules! waker_interrupt { ($INT:ident, $waker:expr) => {{ use core::sync::atomic::{self, Ordering}; + use core::task::Waker; use stm32f4xx_hal::pac::{interrupt, Interrupt, NVIC}; static mut WAKER: Option = None; @@ -359,7 +360,6 @@ macro_rules! waker_interrupt { // This mod MUST go first, so that the others see its macros. pub(crate) mod fmt; -pub mod interrupt; pub mod uarte; pub use cortex_m_rt::interrupt; diff --git a/embassy-stm32f4/src/uarte.rs b/embassy-stm32f4/src/uarte.rs index 7bcd654a8..9e253dd9f 100644 --- a/embassy-stm32f4/src/uarte.rs +++ b/embassy-stm32f4/src/uarte.rs @@ -1,11 +1,12 @@ -//! HAL interface to the UARTE peripheral +//! Async low power UARTE. //! -//! See product specification: -//! -//! - nrf52832: Section 35 -//! - nrf52840: Section 6.34 +//! The peripheral is autmatically enabled and disabled as required to save power. +//! Lowest power consumption can only be guaranteed if the send receive futures +//! are dropped correctly (e.g. not using `mem::forget()`). + use core::cell::UnsafeCell; use core::cmp::min; +use core::future::Future; use core::marker::PhantomPinned; use core::ops::Deref; use core::pin::Pin; @@ -14,10 +15,17 @@ use core::sync::atomic::{compiler_fence, Ordering}; use core::task::{Context, Poll}; use cortex_m::singleton; +use embassy::util::Signal; +use embedded_dma::{StaticReadBuffer, StaticWriteBuffer}; + +use crate::fmt::assert; use crate::hal::dma::config::DmaConfig; use crate::hal::dma::{Channel4, PeripheralToMemory, Stream2, StreamsTuple, Transfer}; +use crate::hal::gpio::gpioa::{PA10, PA9}; use crate::hal::gpio::{Alternate, AF10, AF7, AF9}; use crate::hal::gpio::{Floating, Input, Output, PushPull}; +use crate::hal::pac; +use crate::hal::prelude::*; use crate::hal::rcc::Clocks; use crate::hal::serial::config::{ Config as SerialConfig, DmaConfig as SerialDmaConfig, Parity, StopBits, WordLength, @@ -26,156 +34,51 @@ use crate::hal::serial::Serial; use crate::hal::time::Bps; use crate::interrupt; -use crate::interrupt::CriticalSection; + use crate::pac::Interrupt; use crate::pac::{DMA2, USART1}; use embedded_hal::digital::v2::OutputPin; -// Re-export SVD variants to allow user to directly set values -// pub use uarte0::{baudrate::BAUDRATE_A as Baudrate, config::PARITY_A as Parity}; +// Re-export SVD variants to allow user to directly set values. +// pub use pac::uarte0::{baudrate::BAUDRATE_A as Baudrate, config::PARITY_A as Parity}; -use embassy::io::{AsyncBufRead, AsyncWrite, Result}; -use embassy::util::WakerStore; - -use crate::fmt::{assert, panic, todo, *}; - -//use crate::trace; - -const RINGBUF_SIZE: usize = 512; -struct RingBuf { - buf: [u8; RINGBUF_SIZE], - start: usize, - end: usize, - empty: bool, +/// Interface to the UARTE peripheral +pub struct Uarte { + instance: Serial>, PA10>)>, + usart: USART1, + dma: DMA2, } -impl RingBuf { - fn new() -> Self { - RingBuf { - buf: [0; RINGBUF_SIZE], - start: 0, - end: 0, - empty: true, - } - } - - fn push_buf(&mut self) -> &mut [u8] { - if self.start == self.end && !self.empty { - trace!(" ringbuf: push_buf empty"); - return &mut self.buf[..0]; - } - - let n = if self.start <= self.end { - RINGBUF_SIZE - self.end - } else { - self.start - self.end - }; - - trace!(" ringbuf: push_buf {:?}..{:?}", self.end, self.end + n); - &mut self.buf[self.end..self.end + n] - } - - fn push(&mut self, n: usize) { - trace!(" ringbuf: push {:?}", n); - if n == 0 { - return; - } - - self.end = Self::wrap(self.end + n); - self.empty = false; - } - - fn pop_buf(&mut self) -> &mut [u8] { - if self.empty { - trace!(" ringbuf: pop_buf empty"); - return &mut self.buf[..0]; - } - - let n = if self.end <= self.start { - RINGBUF_SIZE - self.start - } else { - self.end - self.start - }; - - trace!(" ringbuf: pop_buf {:?}..{:?}", self.start, self.start + n); - &mut self.buf[self.start..self.start + n] - } - - fn pop(&mut self, n: usize) { - trace!(" ringbuf: pop {:?}", n); - if n == 0 { - return; - } - - self.start = Self::wrap(self.start + n); - self.empty = self.start == self.end; - } - - fn wrap(n: usize) -> usize { - assert!(n <= RINGBUF_SIZE); - if n == RINGBUF_SIZE { - 0 - } else { - n - } - } +struct State { + tx_done: Signal<()>, + rx_done: Signal, } -#[derive(Copy, Clone, Debug, PartialEq)] -enum RxState { - Idle, - Receiving, - ReceivingReady, - Stopping, -} -#[derive(Copy, Clone, Debug, PartialEq)] -enum TxState { - Idle, - Transmitting(usize), +static STATE: State = State { + tx_done: Signal::new(), + rx_done: Signal::new(), +}; + +pub struct Pins { + pub rxd: PA10>, + pub txd: PA9>, + pub dma: DMA2, + pub usart: USART1, } -/// Interface to a UARTE instance -/// -/// This is a very basic interface that comes with the following limitations: -/// - The UARTE instances share the same address space with instances of UART. -/// You need to make sure that conflicting instances -/// are disabled before using `Uarte`. See product specification: -/// - nrf52832: Section 15.2 -/// - nrf52840: Section 6.1.2 -pub struct Uarte { - started: bool, - state: UnsafeCell>, -} +impl Uarte { + pub fn new(mut pins: Pins, parity: Parity, baudrate: Bps, clocks: Clocks) -> Self { + // // Enable interrupts + // uarte.events_endtx.reset(); + // uarte.events_endrx.reset(); + // uarte + // .intenset + // .write(|w| w.endtx().set().txstopped().set().endrx().set().rxto().set()); + // // TODO: Set interrupt priority? + // interrupt::unpend(interrupt::UARTE0_UART0); + // interrupt::enable(interrupt::UARTE0_UART0); -// public because it needs to be used in Instance::{get_state, set_state}, but -// should not be used outside the module -#[doc(hidden)] -pub struct UarteState { - inner: T, - - rx: RingBuf, - rx_state: RxState, - rx_waker: WakerStore, - - tx: RingBuf, - tx_state: TxState, - tx_waker: WakerStore, - - _pin: PhantomPinned, -} - -#[cfg(any(feature = "52833", feature = "52840"))] -fn port_bit(port: GpioPort) -> bool { - match port { - GpioPort::Port0 => false, - GpioPort::Port1 => true, - } -} - -impl Uarte { - pub fn new(uarte: T, mut pins: Pins, parity: Parity, baudrate: Bps, clocks: Clocks) -> Self { - // Select pins // Serial>, PA10>)> let mut serial = Serial::usart1( pins.usart, @@ -191,411 +94,246 @@ impl Uarte { ) .unwrap(); - let isr = pins.dma.hisr; - // self.isr().$tcifX().bit_is_clear() + let isr = pins.dma.hisr;0 - // Enable interrupts - // serial.listen(Event::Txe); - // serial.listen(Event::Txe); + Uarte { instance: serial, dma: pins.dma, usart: pins.usart } + } - // TODO: Enable idle interrupt? Use DMA interrupt? + /// Sets the baudrate, parity and assigns the pins to the UARTE peripheral. + // TODO: Make it take the same `Pins` structs nrf-hal (with optional RTS/CTS). + // // TODO: #[cfg()] for smaller device variants without port register (nrf52810, ...). + // pub fn configure( + // &mut self, + // rxd: &Pin>, + // txd: &mut Pin>, + // parity: Parity, + // baudrate: Baudrate, + // ) { + // let uarte = &self.instance; + // assert!(uarte.enable.read().enable().is_disabled()); + // + // uarte.psel.rxd.write(|w| { + // let w = unsafe { w.pin().bits(rxd.pin()) }; + // let w = w.port().bit(rxd.port().bit()); + // w.connect().connected() + // }); + // + // txd.set_high().unwrap(); + // uarte.psel.txd.write(|w| { + // let w = unsafe { w.pin().bits(txd.pin()) }; + // let w = w.port().bit(txd.port().bit()); + // w.connect().connected() + // }); + // + // uarte.baudrate.write(|w| w.baudrate().variant(baudrate)); + // uarte.config.write(|w| w.parity().variant(parity)); + // } - // STREAM: Stream, - // CHANNEL: Channel, - // DIR: Direction, - // PERIPHERAL: PeriAddress, - // BUF: WriteBuffer::MemSize> + 'static, - // - // (Stream2, Channel4, Rx, PeripheralToMemory), //USART1_RX - // (Stream7, Channel4, Tx, MemoryToPeripheral), //USART1_TX + // fn enable(&mut self) { + // self.instance.enable.write(|w| w.enable().enabled()); + // } - /* - Taken from https://gist.github.com/thalesfragoso/a07340c5df6eee3b04c42fdc69ecdcb1 - */ + /// Sends serial data. + /// + /// `tx_buffer` is marked as static as per `embedded-dma` requirements. + /// It it safe to use a buffer with a non static lifetime if memory is not + /// reused until the future has finished. + pub fn send<'a, B>(&'a mut self, tx_buffer: B) -> SendFuture<'a, B> + where + B: StaticReadBuffer, + { + // Panic if TX is running which can happen if the user has called + // `mem::forget()` on a previous future after polling it once. + assert!(!self.tx_started()); - // let rcc = unsafe { &*RCC::ptr() }; - // rcc.apb2enr.modify(|_, w| w.adc1en().enabled()); - // rcc.apb2rstr.modify(|_, w| w.adcrst().set_bit()); - // rcc.apb2rstr.modify(|_, w| w.adcrst().clear_bit()); - // let adc = cx.device.ADC1; - // adc.cr2.modify(|_, w| { - // w.dma() - // .enabled() - // .cont() - // .continuous() - // .dds() - // .continuous() - // .adon() - // .enabled() - // }); + self.enable(); - // Configure - //let hardware_flow_control = pins.rts.is_some() && pins.cts.is_some(); - //uarte - // .config - // .write(|w| w.hwfc().bit(hardware_flow_control).parity().variant(parity)); - - // Configure frequency - // uarte.baudrate.write(|w| w.baudrate().variant(baudrate)); - - Uarte { - started: false, - state: UnsafeCell::new(UarteState { - inner: uarte, - - rx: RingBuf::new(), - rx_state: RxState::Idle, - rx_waker: WakerStore::new(), - - tx: RingBuf::new(), - tx_state: TxState::Idle, - tx_waker: WakerStore::new(), - - _pin: PhantomPinned, - }), + SendFuture { + uarte: self, + buf: tx_buffer, } } - fn with_state<'a, R>( - self: Pin<&'a mut Self>, - f: impl FnOnce(Pin<&'a mut UarteState>) -> R, - ) -> R { - let Self { state, started } = unsafe { self.get_unchecked_mut() }; - - interrupt::free(|cs| { - let ptr = state.get(); - - if !*started { - T::set_state(cs, ptr); - - *started = true; - - // safety: safe because critical section ensures only one *mut UartState - // exists at the same time. - unsafe { Pin::new_unchecked(&mut *ptr) }.start(); - } - - // safety: safe because critical section ensures only one *mut UartState - // exists at the same time. - f(unsafe { Pin::new_unchecked(&mut *ptr) }) - }) - } -} - -impl Drop for Uarte { - fn drop(&mut self) { - // stop DMA before dropping, because DMA is using the buffer in `self`. - todo!() - } -} - -impl AsyncBufRead for Uarte { - fn poll_fill_buf(self: Pin<&mut Self>, cx: &mut Context<'_>) -> Poll> { - self.with_state(|s| s.poll_fill_buf(cx)) + fn tx_started(&self) -> bool { + // self.instance.events_txstarted.read().bits() != 0 + false } - fn consume(self: Pin<&mut Self>, amt: usize) { - self.with_state(|s| s.consume(amt)) - } -} + /// Receives serial data. + /// + /// The future is pending until the buffer is completely filled. + /// A common pattern is to use [`stop()`](ReceiveFuture::stop) to cancel + /// unfinished transfers after a timeout to prevent lockup when no more data + /// is incoming. + /// + /// `rx_buffer` is marked as static as per `embedded-dma` requirements. + /// It it safe to use a buffer with a non static lifetime if memory is not + /// reused until the future has finished. + pub fn receive<'a, B>(&'a mut self, rx_buffer: B) -> ReceiveFuture<'a, B> + where + B: StaticWriteBuffer, + { + // Panic if RX is running which can happen if the user has called + // `mem::forget()` on a previous future after polling it once. + assert!(!self.rx_started()); -impl AsyncWrite for Uarte { - fn poll_write(self: Pin<&mut Self>, cx: &mut Context<'_>, buf: &[u8]) -> Poll> { - self.with_state(|s| s.poll_write(cx, buf)) - } -} + self.enable(); -impl UarteState { - pub fn start(self: Pin<&mut Self>) { - interrupt::set_priority(T::interrupt(), interrupt::Priority::Level7); - interrupt::enable(T::interrupt()); - interrupt::pend(T::interrupt()); - } - - fn poll_fill_buf(self: Pin<&mut Self>, cx: &mut Context<'_>) -> Poll> { - let this = unsafe { self.get_unchecked_mut() }; - - // Conservative compiler fence to prevent optimizations that do not - // take in to account actions by DMA. The fence has been placed here, - // before any DMA action has started - compiler_fence(Ordering::SeqCst); - trace!("poll_read"); - - // We have data ready in buffer? Return it. - let buf = this.rx.pop_buf(); - if buf.len() != 0 { - trace!(" got {:?} {:?}", buf.as_ptr() as u32, buf.len()); - return Poll::Ready(Ok(buf)); + ReceiveFuture { + uarte: self, + buf: Some(rx_buffer), } + } - trace!(" empty"); + fn rx_started(&self) -> bool { + self.instance.events_rxstarted.read().bits() != 0 + } +} - if this.rx_state == RxState::ReceivingReady { - trace!(" stopping"); - this.rx_state = RxState::Stopping; - this.inner.tasks_stoprx.write(|w| unsafe { w.bits(1) }); +/// Future for the [`LowPowerUarte::send()`] method. +pub struct SendFuture<'a, B> { + uarte: &'a Uarte, + buf: B, +} + +impl<'a, B> Drop for SendFuture<'a, B> { + fn drop(self: &mut Self) { + if self.uarte.tx_started() { + trace!("stoptx"); + + // Stop the transmitter to minimize the current consumption. + self.uarte + .instance + .tasks_stoptx + .write(|w| unsafe { w.bits(1) }); + self.uarte.instance.events_txstarted.reset(); } - - this.rx_waker.store(cx.waker()); - Poll::Pending } +} - fn consume(self: Pin<&mut Self>, amt: usize) { - let this = unsafe { self.get_unchecked_mut() }; - trace!("consume {:?}", amt); - this.rx.pop(amt); - interrupt::pend(T::interrupt()); - } +impl<'a, B> Future for SendFuture<'a, B> +where + B: StaticReadBuffer, +{ + type Output = (); - fn poll_write(self: Pin<&mut Self>, cx: &mut Context<'_>, buf: &[u8]) -> Poll> { - let this = unsafe { self.get_unchecked_mut() }; + fn poll(self: core::pin::Pin<&mut Self>, cx: &mut Context<'_>) -> Poll<()> { + if self.is_ready() { + Poll::Ready(()) + } else { + // Start DMA transaction + let uarte = &self.uarte.instance; - trace!("poll_write: {:?}", buf.len()); + STATE.tx_done.reset(); - let tx_buf = this.tx.push_buf(); - if tx_buf.len() == 0 { - trace!("poll_write: pending"); - this.tx_waker.store(cx.waker()); - return Poll::Pending; + let (ptr, len) = unsafe { self.buf.read_buffer() }; + // assert!(len <= EASY_DMA_SIZE); + // TODO: panic if buffer is not in SRAM + + compiler_fence(Ordering::SeqCst); + // uarte.txd.ptr.write(|w| unsafe { w.ptr().bits(ptr as u32) }); + // uarte + // .txd + // .maxcnt + // .write(|w| unsafe { w.maxcnt().bits(len as _) }); + + // Start the DMA transfer + // See https://github.com/mwkroening/async-stm32f1xx/blob/78c46d1bff124eae4ebc7a2f4d40e6ed74def8b5/src/serial.rs#L118-L129 + // https://github.com/stm32-rs/stm32f1xx-hal/blob/68fd3d6f282173816fd3181e795988d314cb17d0/src/serial.rs#L649-L671 + + // let first_buffer = singleton!(: [u8; 128] = [0; 128]).unwrap(); + // let second_buffer = singleton!(: [u8; 128] = [0; 128]).unwrap(); + // let triple_buffer = Some(singleton!(: [u8; 128] = [0; 128]).unwrap()); + + let transfer = Transfer::init( + StreamsTuple::new(self.dma).2, + self.usart, + self.buf, + // Some(second_buffer), + None, + DmaConfig::default() + .transfer_complete_interrupt(true) + .memory_increment(true) + .double_buffer(false), + ); + + waker_interrupt!(DMA2_STREAM2, cx.waker().clone()); + Poll::Pending } - - let n = min(tx_buf.len(), buf.len()); - tx_buf[..n].copy_from_slice(&buf[..n]); - this.tx.push(n); - - trace!("poll_write: queued {:?}", n); - - // Conservative compiler fence to prevent optimizations that do not - // take in to account actions by DMA. The fence has been placed here, - // before any DMA action has started - compiler_fence(Ordering::SeqCst); - - interrupt::pend(T::interrupt()); - - Poll::Ready(Ok(n)) } +} - fn on_interrupt(&mut self) { - trace!("irq: start"); - let mut more_work = true; - while more_work { - more_work = false; - match self.rx_state { - RxState::Idle => { - trace!(" irq_rx: in state idle"); +/// Future for the [`Uarte::receive()`] method. +pub struct ReceiveFuture<'a, B> { + uarte: &'a Uarte, + buf: Option, +} - if self.inner.events_rxdrdy.read().bits() != 0 { - trace!(" irq_rx: rxdrdy?????"); - self.inner.events_rxdrdy.reset(); - } +impl<'a, B> Drop for ReceiveFuture<'a, B> { + fn drop(self: &mut Self) { + if self.uarte.rx_started() { + trace!("stoprx"); - if self.inner.events_endrx.read().bits() != 0 { - panic!("unexpected endrx"); - } - - let buf = self.rx.push_buf(); - if buf.len() != 0 { - trace!(" irq_rx: starting {:?}", buf.len()); - self.rx_state = RxState::Receiving; - - // Set up the DMA read - self.inner.rxd.ptr.write(|w| - // The PTR field is a full 32 bits wide and accepts the full range - // of values. - unsafe { w.ptr().bits(buf.as_ptr() as u32) }); - self.inner.rxd.maxcnt.write(|w| - // We're giving it the length of the buffer, so no danger of - // accessing invalid memory. We have verified that the length of the - // buffer fits in an `u8`, so the cast to `u8` is also fine. - // - // The MAXCNT field is at least 8 bits wide and accepts the full - // range of values. - unsafe { w.maxcnt().bits(buf.len() as _) }); - trace!(" irq_rx: buf {:?} {:?}", buf.as_ptr() as u32, buf.len()); - - // Enable RXRDY interrupt. - self.inner.events_rxdrdy.reset(); - self.inner.intenset.write(|w| w.rxdrdy().set()); - - // Start UARTE Receive transaction - self.inner.tasks_startrx.write(|w| - // `1` is a valid value to write to task registers. - unsafe { w.bits(1) }); - } - } - RxState::Receiving => { - trace!(" irq_rx: in state receiving"); - if self.inner.events_rxdrdy.read().bits() != 0 { - trace!(" irq_rx: rxdrdy"); - - // Disable the RXRDY event interrupt - // RXRDY is triggered for every byte, but we only care about whether we have - // some bytes or not. So as soon as we have at least one, disable it, to avoid - // wasting CPU cycles in interrupts. - self.inner.intenclr.write(|w| w.rxdrdy().clear()); - - self.inner.events_rxdrdy.reset(); - - self.rx_waker.wake(); - self.rx_state = RxState::ReceivingReady; - more_work = true; // in case we also have endrx pending - } - } - RxState::ReceivingReady | RxState::Stopping => { - trace!(" irq_rx: in state ReceivingReady"); - - if self.inner.events_rxdrdy.read().bits() != 0 { - trace!(" irq_rx: rxdrdy"); - self.inner.events_rxdrdy.reset(); - } - - if self.inner.events_endrx.read().bits() != 0 { - let n: usize = self.inner.rxd.amount.read().amount().bits() as usize; - trace!(" irq_rx: endrx {:?}", n); - self.rx.push(n); - - self.inner.events_endrx.reset(); - - self.rx_waker.wake(); - self.rx_state = RxState::Idle; - more_work = true; // start another rx if possible - } - } - } + self.uarte + .instance + .tasks_stoprx + .write(|w| unsafe { w.bits(1) }); + self.uarte.instance.events_rxstarted.reset(); } + } +} - more_work = true; - while more_work { - more_work = false; - match self.tx_state { - TxState::Idle => { - trace!(" irq_tx: in state Idle"); - let buf = self.tx.pop_buf(); - if buf.len() != 0 { - trace!(" irq_tx: starting {:?}", buf.len()); - self.tx_state = TxState::Transmitting(buf.len()); +impl<'a, B> Future for ReceiveFuture<'a, B> +where + B: StaticWriteBuffer, +{ + type Output = B; - // Set up the DMA write - self.inner.txd.ptr.write(|w| - // The PTR field is a full 32 bits wide and accepts the full range - // of values. - unsafe { w.ptr().bits(buf.as_ptr() as u32) }); - self.inner.txd.maxcnt.write(|w| - // We're giving it the length of the buffer, so no danger of - // accessing invalid memory. We have verified that the length of the - // buffer fits in an `u8`, so the cast to `u8` is also fine. - // - // The MAXCNT field is 8 bits wide and accepts the full range of - // values. - unsafe { w.maxcnt().bits(buf.len() as _) }); + fn poll(self: core::pin::Pin<&mut Self>, cx: &mut Context<'_>) -> Poll { + if self.is_ready() { + Poll::Ready(()) + } else { + // Start DMA transaction + compiler_fence(Ordering::SeqCst); + // uarte.txd.ptr.write(|w| unsafe { w.ptr().bits(ptr as u32) }); + // uarte + // .txd + // .maxcnt + // .write(|w| unsafe { w.maxcnt().bits(len as _) }); - // Start UARTE Transmit transaction - self.inner.tasks_starttx.write(|w| - // `1` is a valid value to write to task registers. - unsafe { w.bits(1) }); - } - } - TxState::Transmitting(n) => { - trace!(" irq_tx: in state Transmitting"); - // Start the DMA transfer - // See https://github.com/mwkroening/async-stm32f1xx/blob/78c46d1bff124eae4ebc7a2f4d40e6ed74def8b5/src/serial.rs#L118-L129 - // https://github.com/stm32-rs/stm32f1xx-hal/blob/68fd3d6f282173816fd3181e795988d314cb17d0/src/serial.rs#L649-L671 + // Start the DMA transfer + // See https://github.com/mwkroening/async-stm32f1xx/blob/78c46d1bff124eae4ebc7a2f4d40e6ed74def8b5/src/serial.rs#L118-L129 + // https://github.com/stm32-rs/stm32f1xx-hal/blob/68fd3d6f282173816fd3181e795988d314cb17d0/src/serial.rs#L649-L671 - let first_buffer = singleton!(: [u8; 128] = [0; 128]).unwrap(); - let second_buffer = singleton!(: [u8; 128] = [0; 128]).unwrap(); - let triple_buffer = Some(singleton!(: [u8; 128] = [0; 128]).unwrap()); + // let first_buffer = singleton!(: [u8; 128] = [0; 128]).unwrap(); + // let second_buffer = singleton!(: [u8; 128] = [0; 128]).unwrap(); + // let triple_buffer = Some(singleton!(: [u8; 128] = [0; 128]).unwrap()); - let transfer = Transfer::init( - StreamsTuple::new(pins.dma).7, - pins.usart, - first_buffer, - Some(second_buffer), - DmaConfig::default() - .transfer_complete_interrupt(true) - .memory_increment(true) - .double_buffer(true), - ); + let transfer = Transfer::init( + StreamsTuple::new(self.dma).7, + self.usart, + self.buf, + // Some(second_buffer), + None, + DmaConfig::default() + .transfer_complete_interrupt(true) + .memory_increment(true) + .double_buffer(false), + ); - if self.inner.events_endtx.read().bits() != 0 { - self.inner.events_endtx.reset(); - - trace!(" irq_tx: endtx {:?}", n); - self.tx.pop(n); - self.tx_waker.wake(); - self.tx_state = TxState::Idle; - more_work = true; // start another tx if possible - } - } - } + waker_interrupt!(DMA2_STREAM7, cx.waker().clone()); + Poll::Pending } - trace!("irq: end"); } } -pub struct Pins { - pub rxd: PA10>, - pub txd: PA9>, - pub dma: DMA2, - pub usart: USART1, - // pub cts: Option>>, - // pub rts: Option>>, -} - -mod private { - pub trait Sealed {} - - impl Sealed for crate::pac::UARTE0 {} - #[cfg(any(feature = "52833", feature = "52840", feature = "9160"))] - impl Sealed for crate::pac::UARTE1 {} -} - -pub trait Instance: Deref + Sized + private::Sealed { - fn interrupt() -> Interrupt; - - #[doc(hidden)] - fn get_state(_cs: &CriticalSection) -> *mut UarteState; - - #[doc(hidden)] - fn set_state(_cs: &CriticalSection, state: *mut UarteState); -} - -#[interrupt] -unsafe fn DMA2_CHANNEL2() { - interrupt::free(|cs| UARTE0::get_state(cs).as_mut().unwrap().on_interrupt()); -} - -#[interrupt] -unsafe fn DMA2_CHANNEL7() { - interrupt::free(|cs| UARTE1::get_state(cs).as_mut().unwrap().on_interrupt()); -} - -static mut UARTE0_STATE: *mut UarteState = ptr::null_mut(); -#[cfg(any(feature = "52833", feature = "52840", feature = "9160"))] -static mut UARTE1_STATE: *mut UarteState = ptr::null_mut(); - -impl Instance for DMA_CHANNEL1 { - fn interrupt() -> Interrupt { - Interrupt::UARTE0_UART0 - } - - fn get_state(_cs: &CriticalSection) -> *mut UarteState { - unsafe { UARTE0_STATE } // Safe because of CriticalSection - } - fn set_state(_cs: &CriticalSection, state: *mut UarteState) { - unsafe { UARTE0_STATE = state } // Safe because of CriticalSection - } -} - -#[cfg(any(feature = "52833", feature = "52840", feature = "9160"))] -impl Instance for UARTE1 { - fn interrupt() -> Interrupt { - Interrupt::UARTE1 - } - - fn get_state(_cs: &CriticalSection) -> *mut UarteState { - unsafe { UARTE1_STATE } // Safe because of CriticalSection - } - fn set_state(_cs: &CriticalSection, state: *mut UarteState) { - unsafe { UARTE1_STATE = state } // Safe because of CriticalSection +/// Future for the [`receive()`] method. +impl<'a, B> ReceiveFuture<'a, B> { + /// Stops the ongoing reception and returns the number of bytes received. + pub async fn stop(mut self) -> (B, usize) { + let buf = self.buf.take().unwrap(); + drop(self); + let len = STATE.rx_done.wait().await; + (buf, len as _) } }