diff --git a/Cargo.toml b/Cargo.toml index 88472593..5c6090a5 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -11,6 +11,7 @@ members = [ "nrf52840-hal", "nrf9160-hal", "examples/rtfm-demo", + "examples/rtfm-uarte-interrupts", "examples/spi-demo", "examples/twi-ssd1306", ] diff --git a/examples/rtfm-demo/Cargo.toml b/examples/rtfm-demo/Cargo.toml index 4d4ce3da..269d5204 100644 --- a/examples/rtfm-demo/Cargo.toml +++ b/examples/rtfm-demo/Cargo.toml @@ -5,7 +5,7 @@ authors = ["James Munns "] edition = "2018" [dependencies] -cortex-m-rtfm = "0.4.3" +cortex-m-rtfm = "0.4" panic-semihosting = "0.5.1" cortex-m-semihosting = "0.3.3" diff --git a/examples/rtfm-uarte-interrupts/.cargo/config b/examples/rtfm-uarte-interrupts/.cargo/config new file mode 100644 index 00000000..64e3ce85 --- /dev/null +++ b/examples/rtfm-uarte-interrupts/.cargo/config @@ -0,0 +1,5 @@ +[target.thumbv7em-none-eabihf] +runner = "arm-none-eabi-gdb -tui" + +[build] +target = "thumbv7em-none-eabihf" diff --git a/examples/rtfm-uarte-interrupts/.gdbinit b/examples/rtfm-uarte-interrupts/.gdbinit new file mode 100644 index 00000000..ec068055 --- /dev/null +++ b/examples/rtfm-uarte-interrupts/.gdbinit @@ -0,0 +1,10 @@ +set remotetimeout 60000 +target remote :2331 +set arm force-mode thumb + +# Uncomment to enable semihosting, when necessary +monitor semihosting enable + +layout split +monitor reset +load diff --git a/examples/rtfm-uarte-interrupts/Cargo.toml b/examples/rtfm-uarte-interrupts/Cargo.toml new file mode 100644 index 00000000..c6a7ade6 --- /dev/null +++ b/examples/rtfm-uarte-interrupts/Cargo.toml @@ -0,0 +1,36 @@ +[package] +name = "rtfm-uarte-interrupts" +version = "0.1.0" +authors = ["Per Lindgren ", + "Emil Fresk "] +edition = "2018" + +[dependencies] +cortex-m-rtfm = "0.4" +panic-semihosting = "0.5.1" +cortex-m-semihosting = "0.3.3" +heapless = ">= 0.5.0" + +[dependencies.nrf52810-hal] +version = "0.8.0" +path = "../../nrf52810-hal" +optional = true +features = ["UARTE_DMA_SIZE_16"] + +[dependencies.nrf52832-hal] +version = "0.8.0" +path = "../../nrf52832-hal" +optional = true +features = ["xxAB-package", "UARTE_DMA_SIZE_16"] + +[dependencies.nrf52840-hal] +version = "0.8.0" +path = "../../nrf52840-hal" +optional = true +features = ["UARTE_DMA_SIZE_16"] + +[features] +52810 = ["nrf52810-hal"] +52832 = ["nrf52832-hal"] +52840 = ["nrf52840-hal"] +default = ["52832"] diff --git a/examples/rtfm-uarte-interrupts/src/main.rs b/examples/rtfm-uarte-interrupts/src/main.rs new file mode 100644 index 00000000..d360d0e9 --- /dev/null +++ b/examples/rtfm-uarte-interrupts/src/main.rs @@ -0,0 +1,138 @@ +#![no_main] +#![no_std] + +// panic handler +extern crate panic_semihosting; + +use cortex_m_semihosting::hprintln; + +#[cfg(feature = "52810")] +use nrf52810_hal as hal; + +#[cfg(feature = "52832")] +use nrf52832_hal as hal; + +#[cfg(feature = "52840")] +use nrf52840_hal as hal; + +use hal::gpio::{p0, Level}; +use hal::target::{interrupt, TIMER0 as TIM0, UARTE0}; +use hal::timer::*; +use hal::{ + uarte::{ + self, + interrupt_driven::{RXError, UarteDMAPool, UarteDMAPoolNode, UarteRX, UarteTX}, + }, + Uarte, +}; + +use heapless::{ + consts, + pool::singleton::Box, + spsc::{Producer, Queue}, +}; + +// Needed for the write! example code +// use core::fmt::Write; +// use heapless::pool::singleton::Pool; + +use rtfm::app; + +const NR_PACKAGES: usize = 10; +const DMA_MEM: usize = core::mem::size_of::() * NR_PACKAGES; + +// Using power-of-2 constants is faster (see the crate heapless for details) +type TXQSize = consts::U4; + +#[app(device = crate::hal::target)] +const APP: () = { + static mut RX: UarteRX = (); + static mut TX: UarteTX = (); + static mut PRODUCER: Producer<'static, Box, TXQSize> = (); + + #[init(spawn = [])] + fn init() -> init::LateResources { + // for the actual DMA buffers + static mut MEMORY: [u8; DMA_MEM] = [0; DMA_MEM]; + // for the producer/consumer of TX + static mut TX_RB: Queue, TXQSize> = Queue(heapless::i::Queue::new()); + + hprintln!("init").unwrap(); + + let port0 = p0::Parts::new(device.P0); + + let uarte0 = Uarte::new( + device.UARTE0, + uarte::Pins { + // adafruit-nrf52-bluefruit-le, adafruit_nrf52pro, nRF52-DK, nRF52840-DK + txd: port0.p0_06.into_push_pull_output(Level::High).degrade(), + rxd: port0.p0_08.into_floating_input().degrade(), + // Use the following for DWM-1001 dev board + // txd: port0.p0_05.into_push_pull_output(Level::High).degrade(), + // rxd: port0.p0_11.into_floating_input().degrade(), + cts: None, + rts: None, + }, + uarte::Parity::EXCLUDED, + uarte::Baudrate::BAUD115200, + ); + + let timer = Timer::new(device.TIMER0); + let (txp, txc) = TX_RB.split(); + let (rx, tx) = uarte0.into_interrupt_driven(txc, timer, MEMORY); + + init::LateResources { + RX: rx, + TX: tx, + PRODUCER: txp, + } + } + + // // we can get Box

us being now the owner + #[task(capacity = 2, resources = [PRODUCER])] + fn printer(data: Box) { + // enqueue a test message + // let mut node = UarteDMAPool::alloc().unwrap().init(UarteDMAPoolNode::new()); + // write!(&mut node, "test").unwrap(); // Using the write! trait + // node.write_slice(&b"test"[..]); // Using raw slice writing + // resources.PRODUCER.enqueue(node).unwrap(); + // hprintln!("{:?}", &data).unwrap(); + + // Echo the buffer back without any changes or copying + resources.PRODUCER.enqueue(data).unwrap(); + rtfm::pend(interrupt::UARTE0_UART0); + } + + #[task] + fn rx_error(err: RXError) { + hprintln!("rx_error {:?}", err).unwrap(); + } + + #[interrupt(priority = 2, resources = [RX])] + fn TIMER0() { + resources.RX.process_timeout_interrupt(); + } + + #[interrupt(priority = 2, resources = [RX, TX], spawn = [printer, rx_error])] + fn UARTE0_UART0() { + // probe RX + match resources.RX.process_interrupt() { + Ok(Some(b)) => { + // delegate data to printer + match spawn.printer(b) { + Err(_) => spawn.rx_error(RXError::OOM).unwrap(), + _ => (), + }; + } + Ok(None) => (), // no + Err(err) => spawn.rx_error(err).unwrap(), + } + + resources.TX.process_interrupt(); + } + + extern "C" { + fn SWI1_EGU1(); + fn SWI2_EGU2(); + } +}; diff --git a/nrf52-hal-common/Cargo.toml b/nrf52-hal-common/Cargo.toml index 7eece8a3..bf86fd7b 100644 --- a/nrf52-hal-common/Cargo.toml +++ b/nrf52-hal-common/Cargo.toml @@ -22,6 +22,9 @@ nb = "0.1.1" fpa = "0.1.0" rand_core = "0.4.0" +[dependencies.heapless] +version = "0.5.1" + [dependencies.void] default-features = false version = "1.0.2" @@ -58,3 +61,10 @@ default = ["52832"] 52832 = ["nrf52832-pac"] 52840 = ["nrf52840-pac"] 9160 = ["nrf9160-pac"] +UARTE_DMA_SIZE_4 = [] +UARTE_DMA_SIZE_8 = [] +UARTE_DMA_SIZE_16 = [] +UARTE_DMA_SIZE_32 = [] +UARTE_DMA_SIZE_64 = [] +UARTE_DMA_SIZE_128 = [] +UARTE_DMA_SIZE_255 = [] diff --git a/nrf52-hal-common/src/lib.rs b/nrf52-hal-common/src/lib.rs index 7601789e..79d0e494 100644 --- a/nrf52-hal-common/src/lib.rs +++ b/nrf52-hal-common/src/lib.rs @@ -17,12 +17,12 @@ pub use nrf9160_pac as target; pub mod clocks; pub mod delay; pub mod gpio; -#[cfg(not(feature="9160"))] +#[cfg(not(feature = "9160"))] pub mod rng; pub mod rtc; pub mod saadc; pub mod spim; -#[cfg(not(feature="9160"))] +#[cfg(not(feature = "9160"))] pub mod temp; pub mod time; pub mod timer; @@ -46,7 +46,7 @@ pub mod target_constants { pub const SRAM_UPPER: usize = 0x3000_0000; pub const FORCE_COPY_BUFFER_SIZE: usize = 255; } -#[cfg(any(feature = "52840", feature="9160"))] +#[cfg(any(feature = "52840", feature = "9160"))] pub mod target_constants { // NRF52840 and NRF9160 16 bits 1..0xFFFF pub const EASY_DMA_SIZE: usize = 65535; @@ -59,8 +59,7 @@ pub mod target_constants { /// Does this slice reside entirely within RAM? pub(crate) fn slice_in_ram(slice: &[u8]) -> bool { let ptr = slice.as_ptr() as usize; - ptr >= target_constants::SRAM_LOWER && - (ptr + slice.len()) < target_constants::SRAM_UPPER + ptr >= target_constants::SRAM_LOWER && (ptr + slice.len()) < target_constants::SRAM_UPPER } /// A handy structure for converting rust slices into ptr and len pairs @@ -73,10 +72,7 @@ pub(crate) struct DmaSlice { impl DmaSlice { pub fn null() -> Self { - Self { - ptr: 0, - len: 0, - } + Self { ptr: 0, len: 0 } } pub fn from_slice(slice: &[u8]) -> Self { @@ -89,7 +85,7 @@ impl DmaSlice { pub use crate::clocks::Clocks; pub use crate::delay::Delay; -#[cfg(not(feature="9160"))] +#[cfg(not(feature = "9160"))] pub use crate::rng::Rng; pub use crate::rtc::Rtc; pub use crate::saadc::Saadc; diff --git a/nrf52-hal-common/src/timer.rs b/nrf52-hal-common/src/timer.rs index 7b39d68c..8cb099be 100644 --- a/nrf52-hal-common/src/timer.rs +++ b/nrf52-hal-common/src/timer.rs @@ -22,7 +22,6 @@ use core::marker::PhantomData; pub struct OneShot; pub struct Periodic; - /// Interface to a TIMER instance /// /// Right now, this is a very basic interface. The timer will always be @@ -105,6 +104,19 @@ where self.0.cc[1].read().bits() } + /// Clears the interrupt for this timer, external NVIC modification + /// + /// Enables an interrupt that is fired when the timer reaches the value that + /// is given as an argument to `start`. + pub(crate) fn clear_interrupt(&mut self) { + // As of this writing, the timer code only uses + // `cc[0]`/`events_compare[0]`. If the code is extended to use other + // compare registers, the following needs to be adapted. + + // Reset the event, otherwise it will always read `1` from now on. + self.0.events_compare[0].write(|w| w); + } + /// Enables the interrupt for this timer /// /// Enables an interrupt that is fired when the timer reaches the value that diff --git a/nrf52-hal-common/src/uarte.rs b/nrf52-hal-common/src/uarte.rs index 280d7f25..55e22c49 100644 --- a/nrf52-hal-common/src/uarte.rs +++ b/nrf52-hal-common/src/uarte.rs @@ -4,45 +4,38 @@ //! //! - nrf52832: Section 35 //! - nrf52840: Section 6.34 +use core::fmt; use core::ops::Deref; use core::sync::atomic::{compiler_fence, Ordering::SeqCst}; -use core::fmt; + + +#[cfg(feature = "9160")] +use crate::target::{uarte0_ns as uarte0, UARTE0_NS as UARTE0, UARTE1_NS as UARTE1}; use embedded_hal::digital::v2::OutputPin; #[cfg(feature="52840")] use crate::target::UARTE1; -#[cfg(feature="9160")] -use crate::target::{ - uarte0_ns as uarte0, - UARTE0_NS as UARTE0, - UARTE1_NS as UARTE1, -}; +#[cfg(not(feature = "9160"))] +use crate::target::{uarte0, UARTE0}; -#[cfg(not(feature="9160"))] -use crate::target::{ - uarte0, - UARTE0, -}; - -use crate::target_constants::EASY_DMA_SIZE; +use crate::gpio::{Floating, Input, Output, Pin, PushPull}; use crate::prelude::*; -use crate::gpio::{ - Pin, - Output, - PushPull, - Input, - Floating, -}; +use crate::target_constants::EASY_DMA_SIZE; + use crate::timer::{self, Timer}; -// Re-export SVD variants to allow user to directly set values -pub use uarte0::{ - baudrate::BAUDRATEW as Baudrate, - config::PARITYW as Parity, +use heapless::{ + pool::singleton::{Box, Pool}, + spsc::Consumer, + ArrayLength, }; +use interrupt_driven::*; + +// Re-export SVD variants to allow user to directly set values +pub use uarte0::{baudrate::BAUDRATEW as Baudrate, config::PARITYW as Parity}; /// Interface to a UARTE instance /// @@ -54,7 +47,10 @@ pub use uarte0::{ /// - nrf52840: Section 6.1.2 pub struct Uarte(T); -impl Uarte where T: Instance { +impl Uarte +where + T: Instance, +{ pub fn new(uarte: T, mut pins: Pins, parity: Parity, baudrate: Baudrate) -> Self { // Select pins uarte.psel.rxd.write(|w| { @@ -95,21 +91,16 @@ impl Uarte where T: Instance { }); // Enable UARTE instance - uarte.enable.write(|w| - w.enable().enabled() - ); + uarte.enable.write(|w| w.enable().enabled()); // 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) - ); + uarte + .config + .write(|w| w.hwfc().bit(hardware_flow_control).parity().variant(parity)); // Configure frequency - uarte.baudrate.write(|w| - w.baudrate().variant(baudrate) - ); + uarte.baudrate.write(|w| w.baudrate().variant(baudrate)); Uarte(uarte) } @@ -120,11 +111,7 @@ impl Uarte where T: Instance { /// /// The buffer must have a length of at most 255 bytes on the nRF52832 /// and at most 65535 bytes on the nRF52840. - pub fn write(&mut self, - tx_buffer : &[u8], - ) - -> Result<(), Error> - { + pub fn write(&mut self, tx_buffer: &[u8]) -> Result<(), Error> { if tx_buffer.len() > EASY_DMA_SIZE { return Err(Error::TxBufferTooLong); } @@ -151,8 +138,7 @@ impl Uarte where T: Instance { // // The PTR field is a full 32 bits wide and accepts the full range // of values. - unsafe { w.ptr().bits(tx_buffer.as_ptr() as u32) } - ); + unsafe { w.ptr().bits(tx_buffer.as_ptr() as u32) }); self.0.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 @@ -202,11 +188,7 @@ impl Uarte where T: Instance { /// until the buffer is full. /// /// The buffer must have a length of at most 255 bytes - pub fn read(&mut self, - rx_buffer : &mut [u8], - ) - -> Result<(), Error> - { + pub fn read(&mut self, rx_buffer: &mut [u8]) -> Result<(), Error> { self.start_read(rx_buffer)?; // Wait for transmission to end @@ -239,8 +221,10 @@ impl Uarte where T: Instance { &mut self, rx_buffer: &mut [u8], timer: &mut Timer, - cycles: u32 - ) -> Result<(), Error> where I: timer::Instance + cycles: u32, + ) -> Result<(), Error> + where + I: timer::Instance, { // Start the read self.start_read(rx_buffer)?; @@ -303,8 +287,7 @@ impl Uarte where T: Instance { // // The PTR field is a full 32 bits wide and accepts the full range // of values. - unsafe { w.ptr().bits(rx_buffer.as_ptr() as u32) } - ); + unsafe { w.ptr().bits(rx_buffer.as_ptr() as u32) }); self.0.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 @@ -336,8 +319,7 @@ impl Uarte where T: Instance { /// Stop an unfinished UART read transaction and flush FIFO to DMA buffer fn cancel_read(&mut self) { // Stop reception - self.0.tasks_stoprx.write(|w| - unsafe { w.bits(1) }); + self.0.tasks_stoprx.write(|w| unsafe { w.bits(1) }); // Wait for the reception to have stopped while self.0.events_rxto.read().bits() == 0 {} @@ -346,8 +328,7 @@ impl Uarte where T: Instance { self.0.events_rxto.write(|w| w); // Ask UART to flush FIFO to DMA buffer - self.0.tasks_flushrx.write(|w| - unsafe { w.bits(1) }); + self.0.tasks_flushrx.write(|w| unsafe { w.bits(1) }); // Wait for the flush to complete. while self.0.events_endrx.read().bits() == 0 {} @@ -359,9 +340,530 @@ impl Uarte where T: Instance { pub fn free(self) -> T { self.0 } + + /// Splits the UARTE into an interrupt driven transmitter and receiver + /// + /// In needs a `Consumer` to place DMA chunks to send, a `Timer` for checking byte timeouts, + /// and a `&'static mut [u8]` memory block to use. + pub fn into_interrupt_driven( + self, + txc: Consumer<'static, Box, S>, + timer: Timer, + dma_pool_memory: &'static mut [u8], + ) -> (UarteRX, UarteTX) + where + S: ArrayLength>, + I: timer::Instance, + { + debug_assert!( + dma_pool_memory.len() >= core::mem::size_of::() * 2, + "The memory pool needs at least space for 2 `UarteDMAPoolNode`s" + ); + UarteDMAPool::grow(dma_pool_memory); + + let rx = UarteRX::::new(timer); + let tx = UarteTX::::new(txc); + (rx, tx) + } } -impl fmt::Write for Uarte where T: Instance { +/// An interrupt driven implementation of the UARTE peripheral. +/// +/// ## Example +/// +/// ``` +/// +/// ``` +pub mod interrupt_driven { + use core::sync::atomic::{compiler_fence, Ordering::SeqCst}; + use core::{fmt, mem, ptr, slice}; + + use crate::timer::{self, Timer}; + use crate::uarte; + use embedded_hal::timer::{Cancel, CountDown}; + + use heapless::{ + consts, pool, + pool::singleton::{Box, Pool}, + spsc::{Consumer, Queue}, + ArrayLength, + }; + + /// DMA block size + /// Defaults to UARTE_DMA_SIZE = 16 if not explicitly set + #[cfg(not(any( + feature = "UARTE_DMA_SIZE_4", + feature = "UARTE_DMA_SIZE_8", + feature = "UARTE_DMA_SIZE_16", + feature = "UARTE_DMA_SIZE_32", + feature = "UARTE_DMA_SIZE_64", + feature = "UARTE_DMA_SIZE_128", + feature = "UARTE_DMA_SIZE_255" + )))] + pub const UARTE_DMA_SIZE: usize = 16; + + #[cfg(feature = "UARTE_DMA_SIZE_4")] + pub const UARTE_DMA_SIZE: usize = 4; + + #[cfg(feature = "UARTE_DMA_SIZE_8")] + pub const UARTE_DMA_SIZE: usize = 8; + + #[cfg(feature = "UARTE_DMA_SIZE_16")] + pub const UARTE_DMA_SIZE: usize = 16; + + #[cfg(feature = "UARTE_DMA_SIZE_32")] + pub const UARTE_DMA_SIZE: usize = 32; + + #[cfg(feature = "UARTE_DMA_SIZE_64")] + pub const UARTE_DMA_SIZE: usize = 64; + + #[cfg(feature = "UARTE_DMA_SIZE_128")] + pub const UARTE_DMA_SIZE: usize = 128; + + // Currently causes internal OOM, needs fixing + // Maximum DMA size is 255 of the UARTE peripheral, see `MAXCNT` for details + #[cfg(feature = "UARTE_DMA_SIZE_255")] + pub const UARTE_DMA_SIZE: usize = 255; + + // An alternative solution to the above is to define the UARTE_DMA_SIZE + // in a separate (default) crate, which can be overridden + // by a patch in the user Cargo.toml, pointing to + // a local crate with the user defined UARTE_DMA_SIZE constant. + // What would you prefer? + + pool!( + /// Pool allocator for the DMA engine running the transfers, where each node in the + /// allocator is an `UarteDMAPoolNode` + #[allow(non_upper_case_globals)] + UarteDMAPool: UarteDMAPoolNode + ); + + /// Each node in the `UarteDMAPool` consists of this struct. + pub struct UarteDMAPoolNode { + len: u8, + buf: [mem::MaybeUninit; Self::MAX_SIZE], + } + + impl fmt::Debug for UarteDMAPoolNode { + fn fmt(&self, f: &mut fmt::Formatter<'_>) -> fmt::Result { + write!(f, "{:?}", self.read()) + } + } + + impl fmt::Write for UarteDMAPoolNode { + fn write_str(&mut self, s: &str) -> fmt::Result { + let free = Self::MAX_SIZE - self.len as usize; + + if s.len() > free { + Err(fmt::Error) + } else { + self.write_slice(s.as_bytes()); + Ok(()) + } + } + } + + impl UarteDMAPoolNode { + /// The maximum buffer size the node can hold + pub const MAX_SIZE: usize = UARTE_DMA_SIZE; + + /// Creates a new node for the UARTE DMA + pub const fn new() -> Self { + Self { + len: 0, + buf: [mem::MaybeUninit::uninit(); Self::MAX_SIZE], + } + } + + /// Gives a `&mut [u8]` slice to write into with the maximum size, the `commit` method + /// must then be used to set the actual number of bytes written. + /// + /// Note that this function internally first zeros the node's buffer. + /// + /// ## Example + /// + /// ``` + /// + /// ``` + pub fn write(&mut self) -> &mut [u8] { + // Initialize memory with a safe value + self.buf = unsafe { [mem::zeroed(); Self::MAX_SIZE] }; + self.len = Self::MAX_SIZE as _; // Set to max so `commit` may shrink it if needed + + unsafe { slice::from_raw_parts_mut(self.buf.as_mut_ptr() as *mut _, Self::MAX_SIZE) } + } + + /// Used to shrink the current size of the slice in the node, mostly used in conjunction + /// with `write`. + pub fn commit(&mut self, shrink_to: usize) { + // Only shrinking is allowed to remain safe with the `MaybeUninit` + if shrink_to < self.len as _ { + self.len = shrink_to as _; + } + } + + /// Used to write data into the node, and returns how many bytes were written from `buf`. + /// + /// If the node is already partially filled, this will continue filling the node. + pub fn write_slice(&mut self, buf: &[u8]) -> usize { + let free = Self::MAX_SIZE - self.len as usize; + let new_size = buf.len(); + let count = if new_size > free { free } else { new_size }; + + // Used to write data into the `MaybeUninit`, safe based on the size check above + unsafe { + ptr::copy_nonoverlapping( + buf.as_ptr(), + self.buf.as_mut_ptr().offset(self.len as isize) as *mut u8, + count, + ); + } + + self.len = self.len + count as u8; + return count; + } + + /// Clear the node of all data making it empty + pub fn clear(&mut self) { + self.len = 0; + } + + /// Returns a readable slice which maps to the buffers internal data + pub fn read(&self) -> &[u8] { + // Safe as it uses the internal length of valid data + unsafe { slice::from_raw_parts(self.buf.as_ptr() as *const _, self.len as usize) } + } + + /// Reads how many bytes are available + pub fn len(&self) -> usize { + self.len as usize + } + + /// This function is unsafe as it must be used in conjunction with `buffer_address` to + /// write and set the correct number of bytes from a DMA transaction + unsafe fn set_len_from_dma(&mut self, len: u8) { + self.len = len; + } + + unsafe fn buffer_address_for_dma(&self) -> u32 { + self.buf.as_ptr() as u32 + } + + pub const fn max_len() -> usize { + Self::MAX_SIZE + } + } + + /// UARTE RX driver, used in interrupt driven contexts, where `I` is the timer instance. + pub struct UarteRX { + rxq: Queue, consts::U2>, // double buffering of DMA chunks + timer: Timer, // Timer for handling timeouts + _marker: core::marker::PhantomData, + } + + /// Receive error in interrupt driven context + #[derive(Debug)] + pub enum RXError { + /// Out of memory error, global pool is depleted + /// + /// Potential causes: + /// 1. User code is saving the `Box` (and not dropping them) + /// 2. User code running `mem::forget` on the `Box` + /// 3. The pool is too small for the use case + OOM, + } + + impl UarteRX + where + T: uarte::Instance, + I: timer::Instance, + { + /// Construct new UARTE RX, hidden from users - used internally + pub(crate) fn new(timer: Timer) -> Self { + let mut rx = Self { + rxq: Queue::new(), + timer, + _marker: core::marker::PhantomData, + }; + + rx.enable_interrupts(); + rx.prepare_read().unwrap(); + rx.start_read(); + + rx + } + + /// Used internally to set up the proper interrupts + fn enable_interrupts(&mut self) { + // This operation is safe due to type-state programming guaranteeing that the RX and + // TX are unique within the driver + let uarte = unsafe { &*T::ptr() }; + + uarte.inten.modify(|_, w| { + w.endrx() + .set_bit() + .rxstarted() + .set_bit() + .rxto() + .set_bit() + .rxdrdy() + .set_bit() + }); + + self.timer.enable_interrupt(None); + } + + /// Start a UARTE read transaction + fn start_read(&mut self) { + // This operation is safe due to type-state programming guaranteeing that the RX and + // TX are unique within the driver + let uarte = unsafe { &*T::ptr() }; + + // Start UARTE Receive transaction + uarte.tasks_startrx.write(|w| + // `1` is a valid value to write to task registers. + unsafe { w.bits(1) }); + } + + /// Prepare UARTE read transaction + fn prepare_read(&mut self) -> Result<(), RXError> { + // This operation is safe due to type-state programming guaranteeing that the RX and + // TX are within the driver + let uarte = unsafe { &*T::ptr() }; + + // This operation is fast as `UarteDMAPoolNode::new()` does not zero the internal buffer + let b = UarteDMAPool::alloc() + .ok_or(RXError::OOM)? + .init(UarteDMAPoolNode::new()); + + compiler_fence(SeqCst); + + // setup start address + uarte + .rxd + .ptr + .write(|w| unsafe { w.ptr().bits(b.buffer_address_for_dma()) }); + // setup length + uarte + .rxd + .maxcnt + .write(|w| unsafe { w.maxcnt().bits(UarteDMAPoolNode::max_len() as _) }); + + let r = self.rxq.enqueue(b); + debug_assert!(r.is_ok(), "Internal driver error, RX Queue Overflow"); + + Ok(()) + } + + /// Timeout handling for the RX driver - Must be called from the corresponding TIMERx + /// Interrupt handler/task. + pub fn process_timeout_interrupt(&mut self) { + // This operation is safe due to type-state programming guaranteeing that the RX and + // TX are unique within the driver + let uarte = unsafe { &*T::ptr() }; + + // Reset the event, otherwise it will always read `1` from now on. + self.timer.clear_interrupt(); + + // Stop UARTE Receive transaction to generate the Timeout Event + uarte.tasks_stoprx.write(|w| + // `1` is a valid value to write to task registers. + unsafe { w.bits(1) }); + } + + /// Main entry point for the RX driver - Must be called from the corresponding UARTE + /// Interrupt handler/task. + /// + /// Will return: + /// 1. `Ok(Some(Box))` if data was received + /// 2. `Ok(None)` if there was no data, i.e. UARTE interrupt was due to other events + /// 3. `Err(RXError::OOM)` if the memory pool was depleted, see `RXError` for mitigations + pub fn process_interrupt(&mut self) -> Result>, RXError> { + // This operation is safe due to type-state programming guaranteeing that the RX and + // TX are unique within the driver + let uarte = unsafe { &*T::ptr() }; + + // Handles the byte timeout timer + if uarte.events_rxdrdy.read().bits() == 1 { + self.timer.cancel().unwrap(); // Never fails + self.timer.start(10_000_u32); // 10 ms timeout for now + + // Reset the event, otherwise it will always read `1` from now on. + uarte.events_rxdrdy.write(|w| w); + } + + if uarte.events_rxto.read().bits() == 1 { + // Tell UARTE to flush FIFO to DMA buffer + uarte.tasks_flushrx.write(|w| unsafe { w.bits(1) }); + + // Reset the event, otherwise it will always read `1` from now on. + uarte.events_rxto.write(|w| w); + } + + // check if dma rx transaction has started + if uarte.events_rxstarted.read().bits() == 1 { + // DMA transaction has started + self.prepare_read()?; + + // Reset the event, otherwise it will always read `1` from now on. + uarte.events_rxstarted.write(|w| w); + } + + // check if dma transaction finished + if uarte.events_endrx.read().bits() == 1 { + self.timer.cancel().unwrap(); // Never fails + + // our transaction has finished + if let Some(mut ret_b) = self.rxq.dequeue() { + // Read the true number of bytes and set the correct length of the packet + // before returning it + let bytes_read = uarte.rxd.amount.read().bits() as u8; + unsafe { + // This operation is safe as `buffer_address_for_dma` has written + // `bytes_read` number of bytes into the node + ret_b.set_len_from_dma(bytes_read); + } + + // Reset the event, otherwise it will always read `1` from now on. + uarte.events_endrx.write(|w| w); + + self.start_read(); + + return Ok(Some(ret_b)); // ok to return, rx started will be caught later + } else { + debug_assert!(false, "Internal driver error, RX Queue Underflow"); + } + } + + // the interrupt was not RXSTARTED or ENDRX, so no action + Ok(None) + } + } + + /// UARTE TX driver, used in interrupt driven contexts, where `S` is the queue length, + /// can be `U3`, `U4` etc. + pub struct UarteTX + where + S: ArrayLength>, + { + txc: Consumer<'static, Box, S>, // chunks to transmit + current: Option>, + _marker: core::marker::PhantomData, + } + + /// Transmission status in interrupt driven context + #[derive(Debug)] + pub enum TXStatus { + /// Status when a TX packet has been sent and another spot is available in the TX queue + TransmissionFinished, + } + + impl UarteTX + where + T: uarte::Instance, + S: ArrayLength>, + { + /// Construct new UARTE TX, hidden from users - used internally + pub(crate) fn new(txc: Consumer<'static, Box, S>) -> Self { + let mut tx = Self { + txc, + current: None, + _marker: core::marker::PhantomData, + }; + + tx.enable_interrupts(); + tx + } + + /// Used internally to set up the proper interrupts + fn enable_interrupts(&mut self) { + // This operation is safe due to type-state programming guaranteeing that the RX and + // TX are unique within the driver + let uarte = unsafe { &*T::ptr() }; + + uarte.inten.modify(|_, w| w.endtx().set_bit()); + } + + /// Sets up the UARTE to send DMA chunk + fn start_write(&mut self, b: Box) { + // This operation is safe due to type-state programming guaranteeing that the RX and + // TX are unique within the driver + let uarte = unsafe { &*T::ptr() }; + + // Only send if the DMA chunk has data, else drop the `Box` + if b.len() > 0 { + compiler_fence(SeqCst); + + // setup start address + uarte + .txd + .ptr + .write(|w| unsafe { w.ptr().bits(b.buffer_address_for_dma()) }); + + // setup length + uarte + .txd + .maxcnt + .write(|w| unsafe { w.maxcnt().bits(b.len() as _) }); + + // Start UARTE transmit transaction + uarte.tasks_starttx.write(|w| unsafe { w.bits(1) }); + self.current = Some(b); // drops the previous current package + } + } + + /// Main entry point for the TX driver - Must be called from the corresponding UARTE + /// Interrupt handler/task. + pub fn process_interrupt(&mut self) -> Option { + // This operation is safe due to type-state programming guaranteeing that the RX and + // TX are unique within the driver + let uarte = unsafe { &*T::ptr() }; + + // ENDTX event? (DMA transaction finished) + if uarte.events_endtx.read().bits() == 1 { + // our transaction has finished + match self.txc.dequeue() { + None => { + // a ENDTX without an started transaction is an error + debug_assert!( + self.current.is_some(), + "Internal error, ENDTX without current transaction." + ); + + // we don't have any more to send, so drop the current buffer + self.current = None; + } + Some(b) => { + self.start_write(b); + } + } + + // Reset the event, otherwise it will always read `1` from now on. + uarte.events_endtx.write(|w| w); + + Some(TXStatus::TransmissionFinished) + } else { + if self.current.is_none() { + match self.txc.dequeue() { + Some(b) => + // we were idle, so start a new transaction + { + self.start_write(b) + } + None => (), + } + } + + None + } + } + } +} + +impl fmt::Write for Uarte +where + T: Instance, +{ fn write_str(&mut self, s: &str) -> fmt::Result { // Copy all data into an on-stack buffer so we never try to EasyDMA from // flash @@ -382,7 +884,6 @@ pub struct Pins { pub rts: Option>>, } - #[derive(Debug)] pub enum Error { TxBufferTooLong, @@ -393,10 +894,19 @@ pub enum Error { BufferNotInRAM, } +pub trait Instance: Deref { + fn ptr() -> *const uarte0::RegisterBlock; +} -pub trait Instance: Deref {} - -impl Instance for UARTE0 {} +impl Instance for UARTE0 { + fn ptr() -> *const uarte0::RegisterBlock { + UARTE0::ptr() + } +} #[cfg(any(feature="52840", feature="9160"))] -impl Instance for UARTE1 {} +impl Instance for UARTE1 { + fn ptr() -> *const uarte0::RegisterBlock { + UARTE1::ptr() + } +} diff --git a/nrf52810-hal/Cargo.toml b/nrf52810-hal/Cargo.toml index 67ca9e9f..31f38693 100644 --- a/nrf52810-hal/Cargo.toml +++ b/nrf52810-hal/Cargo.toml @@ -42,3 +42,13 @@ version = "0.2.1" doc = [] rt = ["nrf52810-pac/rt"] default = ["rt"] +UARTE_DMA_SIZE_4 = ["nrf52-hal-common/UARTE_DMA_SIZE_4"] +UARTE_DMA_SIZE_8 = ["nrf52-hal-common/UARTE_DMA_SIZE_8"] +UARTE_DMA_SIZE_16 = ["nrf52-hal-common/UARTE_DMA_SIZE_16"] +UARTE_DMA_SIZE_32 = ["nrf52-hal-common/UARTE_DMA_SIZE_32"] +UARTE_DMA_SIZE_64 = ["nrf52-hal-common/UARTE_DMA_SIZE_64"] +UARTE_DMA_SIZE_128 = ["nrf52-hal-common/UARTE_DMA_SIZE_128"] +UARTE_DMA_SIZE_255 = ["nrf52-hal-common/UARTE_DMA_SIZE_255"] + + + diff --git a/nrf52832-hal/Cargo.toml b/nrf52832-hal/Cargo.toml index ea141117..2ba5846b 100644 --- a/nrf52832-hal/Cargo.toml +++ b/nrf52832-hal/Cargo.toml @@ -42,8 +42,16 @@ doc = [] rt = ["nrf52832-pac/rt"] xxAA-package = [] xxAB-package = [] +UARTE_DMA_SIZE_4 = ["nrf52-hal-common/UARTE_DMA_SIZE_4"] +UARTE_DMA_SIZE_8 = ["nrf52-hal-common/UARTE_DMA_SIZE_8"] +UARTE_DMA_SIZE_16 = ["nrf52-hal-common/UARTE_DMA_SIZE_16"] +UARTE_DMA_SIZE_32 = ["nrf52-hal-common/UARTE_DMA_SIZE_32"] +UARTE_DMA_SIZE_64 = ["nrf52-hal-common/UARTE_DMA_SIZE_64"] +UARTE_DMA_SIZE_128 = ["nrf52-hal-common/UARTE_DMA_SIZE_128"] +UARTE_DMA_SIZE_255 = ["nrf52-hal-common/UARTE_DMA_SIZE_255"] + # Note: We use the xxAB package because it has the least amount of available resources. # However, most users will want to use the xxAA package. +# If disabling default features, "DMA_SIZE_XX" should be manually set. default = ["rt", "xxAB-package"] - diff --git a/nrf52840-hal/Cargo.toml b/nrf52840-hal/Cargo.toml index b22a03d9..203b7efc 100644 --- a/nrf52840-hal/Cargo.toml +++ b/nrf52840-hal/Cargo.toml @@ -43,4 +43,13 @@ version = "0.2.1" doc = [] rt = ["nrf52840-pac/rt"] default = ["rt"] +UARTE_DMA_SIZE_4 = ["nrf52-hal-common/UARTE_DMA_SIZE_4"] +UARTE_DMA_SIZE_8 = ["nrf52-hal-common/UARTE_DMA_SIZE_8"] +UARTE_DMA_SIZE_16 = ["nrf52-hal-common/UARTE_DMA_SIZE_16"] +UARTE_DMA_SIZE_32 = ["nrf52-hal-common/UARTE_DMA_SIZE_32"] +UARTE_DMA_SIZE_64 = ["nrf52-hal-common/UARTE_DMA_SIZE_64"] +UARTE_DMA_SIZE_128 = ["nrf52-hal-common/UARTE_DMA_SIZE_128"] +UARTE_DMA_SIZE_255 = ["nrf52-hal-common/UARTE_DMA_SIZE_255"] + +