diff --git a/Cargo.toml b/Cargo.toml index 05f52eb3..e70a0bad 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -13,6 +13,7 @@ members = [ "examples/ppi-demo", "examples/gpiote-demo", "examples/wdt-demo", + "examples/bbq-uarte-demo", ] [profile.dev] @@ -25,3 +26,6 @@ lto = false debug = true lto = true opt-level = "s" + +[patch.crates-io] +nrf-hal-common = { path = "./nrf-hal-common" } diff --git a/examples/bbq-uarte-demo/Cargo.toml b/examples/bbq-uarte-demo/Cargo.toml new file mode 100644 index 00000000..5ddda8b8 --- /dev/null +++ b/examples/bbq-uarte-demo/Cargo.toml @@ -0,0 +1,37 @@ +[package] +name = "bbq-uarte-demo" +version = "0.0.1" +edition = "2018" +authors = [ "James Munns "] + +[dependencies] +cortex-m = "0.6.2" +cortex-m-rtic = "0.5.3" +cortex-m-rt = "0.6.12" +bbqueue = "0.4.6" +embedded-hal = "0.2.3" +rtt-target = {version = "0.2.0", features = ["cortex-m"] } + +nrf52810-hal = { version = "0.11", features = ["rt"], optional = true } +nrf52832-hal = { version = "0.11", features = ["rt"], optional = true } +nrf52840-hal = { version = "0.11", features = ["rt"], optional = true } + +nrf-hal-common = { version = "0.11", features = ["bbq-uarte"] } +panic-reset = "0.1.0" + +[dependencies.panic-persist] +version = "0.2.1" +default-features = false + +# Disable documentation to avoid spurious rustdoc warnings +[[bin]] +name = "bbq-uarte-demo" +doc = false +test = false + +[features] +52810 = ["nrf52810-hal"] +52832 = ["nrf52832-hal"] +52840 = ["nrf52840-hal"] +default = ["52832"] + diff --git a/examples/bbq-uarte-demo/Embed.toml b/examples/bbq-uarte-demo/Embed.toml new file mode 100644 index 00000000..8ac6f9c5 --- /dev/null +++ b/examples/bbq-uarte-demo/Embed.toml @@ -0,0 +1,45 @@ +[default.probe] +# The index of the probe in the connected probe list. +# The protocol to be used for communicating with the target. +protocol = "Swd" +# The speed in kHz of the data link to the target. +# speed = 1337 + +[default.flashing] +# Whether or not the target should be flashed. +enabled = true +# Whether or not the target should be halted after flashing. +halt_afterwards = false +# Whether or not bytes erased but not rewritten with data from the ELF +# should be restored with their contents before erasing. +restore_unwritten_bytes = false +# The path where an SVG of the assembled flash layout should be written to. +# flash_layout_output_path = "out.svg" + +[default.general] +# The chip name of the chip to be debugged. +chip = "nRF52832_xxAA" +# A list of chip descriptions to be loaded during runtime. +chip_descriptions = [] +# The default log level to be used. +log_level = "Warn" + +[default.rtt] +# Whether or not an RTTUI should be opened after flashing. +# This is exclusive and cannot be used with GDB at the moment. +enabled = true +# A list of channel associations to be displayed. If left empty, all channels are displayed. +channels = [ + # { up = 0, down = 0, name = "name" } +] +# The duration in ms for which the logger should retry to attach to RTT. +timeout = 3000 +# Whether timestamps in the RTTUI are enabled +show_timestamps = true + +[default.gdb] +# Whether or not a GDB server should be opened after flashing. +# This is exclusive and cannot be used with RTT at the moment. +enabled = false +# The connection string in host:port format wher the GDB server will open a socket. +# gdb_connection_string diff --git a/examples/bbq-uarte-demo/debug.gdb b/examples/bbq-uarte-demo/debug.gdb new file mode 100644 index 00000000..0a0f2b41 --- /dev/null +++ b/examples/bbq-uarte-demo/debug.gdb @@ -0,0 +1,7 @@ +target remote :2331 +set backtrace limit 32 +load +monitor reset +break main +layout split +continue diff --git a/examples/bbq-uarte-demo/src/main.rs b/examples/bbq-uarte-demo/src/main.rs new file mode 100644 index 00000000..2a630319 --- /dev/null +++ b/examples/bbq-uarte-demo/src/main.rs @@ -0,0 +1,129 @@ +#![no_std] +#![no_main] + +// Import the right HAL/PAC crate, depending on the target chip +#[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 { + bbqueue::{consts::*, BBBuffer, ConstBBBuffer}, + core::sync::atomic::AtomicBool, + hal::{ + gpio::Level, + pac::{TIMER1, TIMER2}, + ppi::{Parts, Ppi0}, + Timer, + }, + rtt_target::{rprintln, rtt_init_print}, +}; + +use hal::pac::UARTE0; + +// Panic provider crate +use panic_reset as _; + +#[rtic::app(device = crate::hal::pac, peripherals = true)] +const APP: () = { + struct Resources { + timer: Timer, + + uarte_timer: hal::bbq_uarte::irq::UarteTimer, + uarte_irq: hal::bbq_uarte::irq::UarteIrq, + uarte_app: hal::bbq_uarte::app::UarteApp, + } + + #[init] + fn init(ctx: init::Context) -> init::LateResources { + let _clocks = hal::clocks::Clocks::new(ctx.device.CLOCK).enable_ext_hfosc(); + + let p0 = hal::gpio::p0::Parts::new(ctx.device.P0); + + let uart = ctx.device.UARTE0; + + static UBUF: hal::bbq_uarte::buffer::UarteBuffer = + hal::bbq_uarte::buffer::UarteBuffer { + txd_buf: BBBuffer(ConstBBBuffer::new()), + rxd_buf: BBBuffer(ConstBBBuffer::new()), + timeout_flag: AtomicBool::new(false), + }; + + rtt_init_print!(); + + let rxd = p0.p0_11.into_floating_input().degrade(); + let txd = p0.p0_05.into_push_pull_output(Level::Low).degrade(); + + let ppi_channels = Parts::new(ctx.device.PPI); + let channel0 = ppi_channels.ppi0; + + let uarte_pins = hal::uarte::Pins { + rxd, + txd, + cts: None, + rts: None, + }; + + let ue = UBUF + .try_split( + uarte_pins, + hal::uarte::Parity::EXCLUDED, + hal::uarte::Baudrate::BAUD230400, + ctx.device.TIMER2, + channel0, + uart, + 32, + 1_000_000, + ) + .unwrap(); + + init::LateResources { + timer: Timer::new(ctx.device.TIMER1), + uarte_timer: ue.timer, + uarte_irq: ue.irq, + uarte_app: ue.app, + } + } + + #[idle(resources = [timer, uarte_app])] + fn idle(ctx: idle::Context) -> ! { + let timer = ctx.resources.timer; + let uarte_app = ctx.resources.uarte_app; + + use embedded_hal::timer::CountDown; + + rprintln!("Start!"); + + timer.start(5_000_000u32); + + loop { + if let Ok(rgr) = uarte_app.read() { + let len = rgr.len(); + rprintln!("Brr: {}", len); + if let Ok(mut wgr) = uarte_app.write_grant(len) { + wgr.copy_from_slice(&rgr); + wgr.commit(len); + } + rgr.release(len); + } + if timer.wait().is_ok() { + rprintln!("Hello from idle!"); + timer.start(5_000_000u32); + } + } + } + + #[task(binds = TIMER2, resources = [uarte_timer])] + fn timer2(ctx: timer2::Context) { + // rprintln!("Hello from timer2!"); + ctx.resources.uarte_timer.interrupt(); + } + + #[task(binds = UARTE0_UART0, resources = [uarte_irq])] + fn uarte0(ctx: uarte0::Context) { + // rprintln!("Hello from uarte0!"); + ctx.resources.uarte_irq.interrupt(); + } +}; diff --git a/nrf-hal-common/Cargo.toml b/nrf-hal-common/Cargo.toml index 083b4b3b..985d8efe 100644 --- a/nrf-hal-common/Cargo.toml +++ b/nrf-hal-common/Cargo.toml @@ -61,6 +61,10 @@ version = "0.2.1" features = ["unproven"] version = "0.2.4" +[dependencies.bbqueue] +optional = true +version = "0.4.6" + [features] doc = [] 51 = ["nrf51"] @@ -69,3 +73,6 @@ doc = [] 52833 = ["nrf52833-pac"] 52840 = ["nrf52840-pac"] 9160 = ["nrf9160-pac"] + +# Batteries Included options +bbq-uarte = ["bbqueue"] diff --git a/nrf-hal-common/src/bbq_uarte/app.rs b/nrf-hal-common/src/bbq_uarte/app.rs new file mode 100644 index 00000000..4734e205 --- /dev/null +++ b/nrf-hal-common/src/bbq_uarte/app.rs @@ -0,0 +1,125 @@ +use crate::pac::{Interrupt, NVIC}; +use bbqueue::{ArrayLength, Consumer, Error, GrantR, GrantW, Producer}; +use core::ops::{Deref, DerefMut}; + +pub struct UarteApp +where + OutgoingLen: ArrayLength, + IncomingLen: ArrayLength, +{ + pub(crate) outgoing_prod: Producer<'static, OutgoingLen>, + pub incoming_cons: Consumer<'static, IncomingLen>, +} + +impl UarteApp +where + OutgoingLen: ArrayLength, + IncomingLen: ArrayLength, +{ + pub fn read(&mut self) -> Result, Error> { + self.incoming_cons + .read() + .map(|gr| UarteGrantR { grant_r: gr }) + } + + pub fn write_grant( + &mut self, + bytes: usize, + ) -> Result, Error> { + self.outgoing_prod + .grant_exact(bytes) + .map(|gr| UarteGrantW { grant_w: gr }) + } +} + +/// A write grant for a single Uarte +/// +/// NOTE: If the grant is dropped without explicitly commiting +/// the contents, then no Uarte will be comitted for writing. +#[derive(Debug, PartialEq)] +pub struct UarteGrantW<'a, N> +where + N: ArrayLength, +{ + grant_w: GrantW<'a, N>, +} + +/// A read grant for a single Uarte +/// +/// NOTE: If the grant is dropped without explicitly releasing +/// the contents, then no Uarte will be released. +#[derive(Debug, PartialEq)] +pub struct UarteGrantR<'a, N> +where + N: ArrayLength, +{ + grant_r: GrantR<'a, N>, +} + +impl<'a, N> Deref for UarteGrantW<'a, N> +where + N: ArrayLength, +{ + type Target = [u8]; + + fn deref(&self) -> &Self::Target { + &self.grant_w + } +} + +impl<'a, N> DerefMut for UarteGrantW<'a, N> +where + N: ArrayLength, +{ + fn deref_mut(&mut self) -> &mut [u8] { + &mut self.grant_w + } +} + +impl<'a, N> Deref for UarteGrantR<'a, N> +where + N: ArrayLength, +{ + type Target = [u8]; + + fn deref(&self) -> &Self::Target { + &self.grant_r + } +} + +impl<'a, N> DerefMut for UarteGrantR<'a, N> +where + N: ArrayLength, +{ + fn deref_mut(&mut self) -> &mut [u8] { + &mut self.grant_r + } +} + +impl<'a, N> UarteGrantW<'a, N> +where + N: ArrayLength, +{ + /// Commit a Uarte to make it available to the Consumer half. + /// + /// `used` is the size of the payload, in bytes, not + /// including the Uarte header + pub fn commit(self, used: usize) { + // Commit the header + Uarte + self.grant_w.commit(used); + NVIC::pend(Interrupt::UARTE0_UART0); + } +} + +impl<'a, N> UarteGrantR<'a, N> +where + N: ArrayLength, +{ + /// Release a Uarte to make the space available for future writing + /// + /// Note: The full Uarte is always released + pub fn release(self, used: usize) { + self.grant_r.release(used); + NVIC::pend(Interrupt::UARTE0_UART0); + } +} diff --git a/nrf-hal-common/src/bbq_uarte/buffer.rs b/nrf-hal-common/src/bbq_uarte/buffer.rs new file mode 100644 index 00000000..f653335d --- /dev/null +++ b/nrf-hal-common/src/bbq_uarte/buffer.rs @@ -0,0 +1,107 @@ +use bbqueue::{ArrayLength, BBBuffer}; + +use crate::bbq_uarte::{ + app::UarteApp, + irq::{UarteIrq, UarteTimer}, + Error, +}; +use crate::ppi::{ConfigurablePpi, Ppi}; +use crate::timer::Instance as TimerInstance; +use crate::uarte::{Baudrate, Instance as UarteInstance, Parity, Pins}; +use core::sync::atomic::AtomicBool; + +use crate::pac::{Interrupt, TIMER0, TIMER1, TIMER2}; +#[cfg(any(feature = "52832", feature = "52840"))] +use crate::pac::{TIMER3, TIMER4}; + +pub struct UarteBuffer +where + OutgoingLen: ArrayLength, + IncomingLen: ArrayLength, +{ + pub txd_buf: BBBuffer, + pub rxd_buf: BBBuffer, + pub timeout_flag: AtomicBool, +} + +pub struct UarteParts +where + OutgoingLen: ArrayLength, + IncomingLen: ArrayLength, + Timer: TimerInstance, + Channel: Ppi + ConfigurablePpi, + Uarte: UarteInstance, +{ + pub app: UarteApp, + pub timer: UarteTimer, + pub irq: UarteIrq, +} + +impl UarteBuffer +where + OutgoingLen: ArrayLength, + IncomingLen: ArrayLength, +{ + pub fn try_split( + &'static self, + pins: Pins, + parity: Parity, + baudrate: Baudrate, + timer: Timer, + mut ppi_ch: Channel, + uarte: Uarte, + rx_block_size: usize, + idle_us: u32, + ) -> Result, Error> { + let (txd_prod, txd_cons) = self.txd_buf.try_split().map_err(|e| Error::Bbqueue(e))?; + let (rxd_prod, rxd_cons) = self.rxd_buf.try_split().map_err(|e| Error::Bbqueue(e))?; + + // hmmm + let hw_timer = match Timer::INTERRUPT { + Interrupt::TIMER0 => TIMER0::ptr(), + Interrupt::TIMER1 => TIMER1::ptr(), + Interrupt::TIMER2 => TIMER2::ptr(), + + #[cfg(any(feature = "52832", feature = "52840"))] + Interrupt::TIMER3 => TIMER3::ptr().cast(), // double yolo + + #[cfg(any(feature = "52832", feature = "52840"))] + Interrupt::TIMER4 => TIMER4::ptr().cast(), // double yolo + + _ => unreachable!(), + }; + + let mut utim = UarteTimer { + timer, + timeout_flag: &self.timeout_flag, + interrupt: Uarte::INTERRUPT, + }; + + ppi_ch.set_task_endpoint(unsafe { &(&*hw_timer).tasks_clear }); + ppi_ch.set_event_endpoint(&uarte.events_rxdrdy); + + let mut uirq = UarteIrq { + incoming_prod: rxd_prod, + outgoing_cons: txd_cons, + timeout_flag: &self.timeout_flag, + rx_grant: None, + tx_grant: None, + uarte, + block_size: rx_block_size, + ppi_ch, + }; + + utim.init(idle_us); + uirq.init(pins, parity, baudrate); + + // ... + Ok(UarteParts { + app: UarteApp { + outgoing_prod: txd_prod, + incoming_cons: rxd_cons, + }, + irq: uirq, + timer: utim, + }) + } +} diff --git a/nrf-hal-common/src/bbq_uarte/irq.rs b/nrf-hal-common/src/bbq_uarte/irq.rs new file mode 100644 index 00000000..c23458d9 --- /dev/null +++ b/nrf-hal-common/src/bbq_uarte/irq.rs @@ -0,0 +1,179 @@ +use crate::{ + pac::{Interrupt, NVIC}, + ppi::{ConfigurablePpi, Ppi}, + target_constants::EASY_DMA_SIZE, + timer::Instance as TimerInstance, + uarte::{ + uarte_cancel_read, uarte_setup, uarte_start_read, uarte_start_write, Baudrate, + Instance as UarteInstance, Parity, Pins, + }, +}; +use bbqueue::{ArrayLength, Consumer, GrantR, GrantW, Producer}; +use core::sync::atomic::{compiler_fence, AtomicBool, Ordering::SeqCst}; + +pub struct UarteTimer +where + Timer: TimerInstance, +{ + pub(crate) timer: Timer, + pub(crate) timeout_flag: &'static AtomicBool, + pub(crate) interrupt: Interrupt, +} + +impl UarteTimer +where + Timer: TimerInstance, +{ + pub fn init(&mut self, microsecs: u32) { + self.timer.disable_interrupt(); + self.timer.timer_cancel(); + self.timer.set_periodic(); + self.timer.set_shorts_periodic(); + self.timer.enable_interrupt(); + + self.timer.timer_start(microsecs); + } + + pub fn interrupt(&self) { + // pend uarte interrupt + self.timer.timer_reset_event(); + self.timeout_flag.store(true, SeqCst); + NVIC::pend(self.interrupt); + } +} + +pub struct UarteIrq +where + OutgoingLen: ArrayLength, + IncomingLen: ArrayLength, + Channel: Ppi + ConfigurablePpi, + Uarte: UarteInstance, +{ + pub(crate) outgoing_cons: Consumer<'static, OutgoingLen>, + pub(crate) incoming_prod: Producer<'static, IncomingLen>, + pub(crate) timeout_flag: &'static AtomicBool, + pub(crate) rx_grant: Option>, + pub(crate) tx_grant: Option>, + pub(crate) uarte: Uarte, + pub(crate) block_size: usize, + pub(crate) ppi_ch: Channel, +} + +impl UarteIrq +where + OutgoingLen: ArrayLength, + IncomingLen: ArrayLength, + Channel: Ppi + ConfigurablePpi, + Uarte: UarteInstance, +{ + pub fn init(&mut self, pins: Pins, parity: Parity, baudrate: Baudrate) { + uarte_setup(&self.uarte, pins, parity, baudrate); + + // Clear all interrupts + self.uarte.intenclr.write(|w| unsafe { w.bits(0xFFFFFFFF) }); + + // Enable relevant interrupts + self.uarte.intenset.write(|w| { + w.endrx().set_bit(); + w.endtx().set_bit(); + w.error().set_bit(); + w + }); + + self.ppi_ch.enable(); + + if let Ok(mut gr) = self.incoming_prod.grant_exact(self.block_size) { + uarte_start_read(&self.uarte, &mut gr).unwrap(); + self.rx_grant = Some(gr); + } + } + + pub fn interrupt(&mut self) { + let endrx = self.uarte.events_endrx.read().bits() != 0; + let endtx = self.uarte.events_endtx.read().bits() != 0; + let rxdrdy = self.uarte.events_rxdrdy.read().bits() != 0; + let error = self.uarte.events_error.read().bits() != 0; + let txstopped = self.uarte.events_txstopped.read().bits() != 0; + + let timeout = self.timeout_flag.swap(false, SeqCst); + let errsrc = self.uarte.errorsrc.read().bits(); + + // RX section + if endrx || timeout || self.rx_grant.is_none() { + // We only flush the connection if: + // + // * We didn't get a "natural" end of reception (full buffer), AND + // * The timer expired, AND + // * We have received one or more bytes to the receive buffer + if !endrx && timeout && rxdrdy { + uarte_cancel_read(&self.uarte); + } + + compiler_fence(SeqCst); + + // Get the bytes received. If the rxdrdy flag wasn't set, then we haven't + // actually received any bytes, and we can't trust the `amount` field + // (it may have a stale value from the last reception) + let amt = if rxdrdy { + self.uarte.rxd.amount.read().bits() as usize + } else { + 0 + }; + + // If we received data, cycle the grant and get a new one + if amt != 0 || self.rx_grant.is_none() { + let gr = self.rx_grant.take(); + + // If the buffer was full last time, we may not actually have a grant right now + if let Some(gr) = gr { + gr.commit(amt); + } + + // Attempt to get the next grant. If we don't get one now, no worries, + // we'll try again on the next timeout + if let Ok(mut gr) = self.incoming_prod.grant_exact(self.block_size) { + uarte_start_read(&self.uarte, &mut gr).unwrap(); + self.rx_grant = Some(gr); + } + } + } + + // TX Section + if endtx || self.tx_grant.is_none() { + if endtx { + if let Some(gr) = self.tx_grant.take() { + let len = gr.len(); + gr.release(len.min(EASY_DMA_SIZE)); + } + } + + if let Ok(gr) = self.outgoing_cons.read() { + let len = gr.len(); + uarte_start_write(&self.uarte, &gr[..len.min(EASY_DMA_SIZE)]).unwrap(); + self.tx_grant = Some(gr); + } + } + + // Clear events we processed + if endrx { + self.uarte.events_endrx.write(|w| w); + } + if endtx { + self.uarte.events_endtx.write(|w| w); + } + if error { + self.uarte.events_error.write(|w| w); + } + if rxdrdy { + self.uarte.events_rxdrdy.write(|w| w); + } + if txstopped { + self.uarte.events_txstopped.write(|w| w); + } + + // Clear any errors + if errsrc != 0 { + self.uarte.errorsrc.write(|w| unsafe { w.bits(errsrc) }); + } + } +} diff --git a/nrf-hal-common/src/bbq_uarte/mod.rs b/nrf-hal-common/src/bbq_uarte/mod.rs new file mode 100644 index 00000000..8c6683cc --- /dev/null +++ b/nrf-hal-common/src/bbq_uarte/mod.rs @@ -0,0 +1,9 @@ +pub mod app; +pub mod buffer; +pub mod irq; +use bbqueue::Error as BbqError; + +#[derive(Debug)] +pub enum Error { + Bbqueue(BbqError), +} diff --git a/nrf-hal-common/src/lib.rs b/nrf-hal-common/src/lib.rs index 31941626..9fe16e1f 100644 --- a/nrf-hal-common/src/lib.rs +++ b/nrf-hal-common/src/lib.rs @@ -63,6 +63,9 @@ pub mod uicr; #[cfg(not(feature = "9160"))] pub mod wdt; +#[cfg(feature = "bbq-uarte")] +pub mod bbq_uarte; + pub mod prelude { pub use crate::hal::digital::v2::*; pub use crate::hal::prelude::*; diff --git a/nrf-hal-common/src/uarte.rs b/nrf-hal-common/src/uarte.rs index 46d09ce6..6fbef803 100644 --- a/nrf-hal-common/src/uarte.rs +++ b/nrf-hal-common/src/uarte.rs @@ -19,6 +19,9 @@ use crate::pac::{uarte0_ns as uarte0, UARTE0_NS as UARTE0, UARTE1_NS as UARTE1}; #[cfg(not(feature = "9160"))] use crate::pac::{uarte0, UARTE0}; +#[cfg(feature = "bbq-uarte")] +use crate::pac::Interrupt; + use crate::gpio::{Floating, Input, Output, Pin, PushPull}; use crate::prelude::*; use crate::slice_in_ram_or; @@ -42,57 +45,8 @@ 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| { - let w = unsafe { w.pin().bits(pins.rxd.pin()) }; - #[cfg(any(feature = "52833", feature = "52840"))] - let w = w.port().bit(pins.rxd.port().bit()); - w.connect().connected() - }); - pins.txd.set_high().unwrap(); - uarte.psel.txd.write(|w| { - let w = unsafe { w.pin().bits(pins.txd.pin()) }; - #[cfg(any(feature = "52833", feature = "52840"))] - let w = w.port().bit(pins.txd.port().bit()); - w.connect().connected() - }); - - // Optional pins - uarte.psel.cts.write(|w| { - if let Some(ref pin) = pins.cts { - let w = unsafe { w.pin().bits(pin.pin()) }; - #[cfg(any(feature = "52833", feature = "52840"))] - let w = w.port().bit(pin.port().bit()); - w.connect().connected() - } else { - w.connect().disconnected() - } - }); - - uarte.psel.rts.write(|w| { - if let Some(ref pin) = pins.rts { - let w = unsafe { w.pin().bits(pin.pin()) }; - #[cfg(any(feature = "52833", feature = "52840"))] - let w = w.port().bit(pin.port().bit()); - w.connect().connected() - } else { - w.connect().disconnected() - } - }); - - // Enable UARTE instance. - 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)); - - // Configure frequency. - uarte.baudrate.write(|w| w.baudrate().variant(baudrate)); - + pub fn new(uarte: T, pins: Pins, parity: Parity, baudrate: Baudrate) -> Self { + uarte_setup(&uarte, pins, parity, baudrate); Uarte(uarte) } @@ -103,44 +57,9 @@ where /// 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> { - if tx_buffer.len() > EASY_DMA_SIZE { - return Err(Error::TxBufferTooLong); - } - - // We can only DMA out of RAM. - slice_in_ram_or(tx_buffer, Error::BufferNotInRAM)?; - - // 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(SeqCst); + uarte_start_write(&self.0, tx_buffer)?; - // Reset the events. - self.0.events_endtx.reset(); - self.0.events_txstopped.reset(); - - // Set up the DMA write. - self.0.txd.ptr.write(|w| - // We're giving the register a pointer to the stack. Since we're - // waiting for the UARTE transaction to end before this stack pointer - // becomes invalid, there's nothing wrong here. - // - // 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) }); - 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 - // 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(tx_buffer.len() as _) }); - - // Start UARTE Transmit transaction. - self.0.tasks_starttx.write(|w| - // `1` is a valid value to write to task registers. - unsafe { w.bits(1) }); + ////// AJM // Wait for transmission to end. let mut endtx; @@ -178,7 +97,7 @@ where /// /// The buffer must have a length of at most 255 bytes. pub fn read(&mut self, rx_buffer: &mut [u8]) -> Result<(), Error> { - self.start_read(rx_buffer)?; + uarte_start_read(&self.0, rx_buffer)?; // Wait for transmission to end. while self.0.events_endrx.read().bits() == 0 {} @@ -216,7 +135,7 @@ where I: timer::Instance, { // Start the read. - self.start_read(rx_buffer)?; + uarte_start_read(&self.0, rx_buffer)?; // Start the timeout timer. timer.start(cycles); @@ -235,7 +154,7 @@ where if !event_complete { // Cancel the reception if it did not complete until now. - self.cancel_read(); + uarte_cancel_read(&self.0); } // Cleanup, even in the error case. @@ -254,49 +173,6 @@ where Ok(()) } - /// Start a UARTE read transaction by setting the control - /// values and triggering a read task. - fn start_read(&mut self, rx_buffer: &mut [u8]) -> Result<(), Error> { - // This is overly restrictive. See (similar SPIM issue): - // https://github.com/nrf-rs/nrf52/issues/17 - if rx_buffer.len() > u8::max_value() as usize { - return Err(Error::TxBufferTooLong); - } - - // NOTE: RAM slice check is not necessary, as a mutable slice can only be - // built from data located in RAM. - - // 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(SeqCst); - - // Set up the DMA read - self.0.rxd.ptr.write(|w| - // We're giving the register a pointer to the stack. Since we're - // waiting for the UARTE transaction to end before this stack pointer - // becomes invalid, there's nothing wrong here. - // - // 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) }); - 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 - // 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(rx_buffer.len() as _) }); - - // Start UARTE Receive transaction. - self.0.tasks_startrx.write(|w| - // `1` is a valid value to write to task registers. - unsafe { w.bits(1) }); - - Ok(()) - } - /// Finalize a UARTE read transaction by clearing the event. fn finalize_read(&mut self) { // Reset the event, otherwise it will always read `1` from now on. @@ -308,26 +184,6 @@ where compiler_fence(SeqCst); } - /// 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) }); - - // Wait for the reception to have stopped. - while self.0.events_rxto.read().bits() == 0 {} - - // Reset the event flag. - 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) }); - - // Wait for the flush to complete. - while self.0.events_endrx.read().bits() == 0 {} - - // The event flag itself is later reset by `finalize_read`. - } - /// Return the raw interface to the underlying UARTE peripheral. pub fn free(self) -> T { self.0 @@ -351,6 +207,171 @@ where } } +/// Start a UARTE read transaction by setting the control +/// values and triggering a read task +pub(crate) fn uarte_start_read(uarte: &T, rx_buffer: &mut [u8]) -> Result<(), Error> { + // This is overly restrictive. See (similar SPIM issue): + // https://github.com/nrf-rs/nrf52/issues/17 + if rx_buffer.len() > u8::max_value() as usize { + return Err(Error::RxBufferTooLong); + } + + // NOTE: RAM slice check is not necessary, as a mutable slice can only be + // built from data located in RAM + + // 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(SeqCst); + + // Set up the DMA read + uarte.rxd.ptr.write(|w| + // We're giving the register a pointer to the stack. Since we're + // waiting for the UARTE transaction to end before this stack pointer + // becomes invalid, there's nothing wrong here. + // + // 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) }); + uarte.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(rx_buffer.len() as _) }); + + // Start UARTE Receive transaction + uarte.tasks_startrx.write(|w| + // `1` is a valid value to write to task registers. + unsafe { w.bits(1) }); + + Ok(()) +} + +pub(crate) fn uarte_start_write(uarte: &T, tx_buffer: &[u8]) -> Result<(), Error> { + if tx_buffer.len() > EASY_DMA_SIZE { + return Err(Error::TxBufferTooLong); + } + + // We can only DMA out of RAM. + slice_in_ram_or(tx_buffer, Error::BufferNotInRAM)?; + + // 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(SeqCst); + + // Reset the events. + uarte.events_endtx.reset(); + uarte.events_txstopped.reset(); + + // Set up the DMA write + uarte.txd.ptr.write(|w| + // We're giving the register a pointer to the stack. Since we're + // waiting for the UARTE transaction to end before this stack pointer + // becomes invalid, there's nothing wrong here. + // + // 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) }); + uarte.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(tx_buffer.len() as _) }); + + // Start UARTE Transmit transaction + uarte.tasks_starttx.write(|w| + // `1` is a valid value to write to task registers. + unsafe { w.bits(1) }); + + Ok(()) +} + +pub(crate) fn uarte_setup( + uarte: &T, + mut pins: Pins, + parity: Parity, + baudrate: Baudrate, +) { + // Select pins + uarte.psel.rxd.write(|w| { + let w = unsafe { w.pin().bits(pins.rxd.pin()) }; + #[cfg(feature = "52840")] + let w = w.port().bit(pins.rxd.port().bit()); + w.connect().connected() + }); + pins.txd.set_high().unwrap(); + uarte.psel.txd.write(|w| { + let w = unsafe { w.pin().bits(pins.txd.pin()) }; + #[cfg(feature = "52840")] + let w = w.port().bit(pins.txd.port().bit()); + w.connect().connected() + }); + + // Optional pins + uarte.psel.cts.write(|w| { + if let Some(ref pin) = pins.cts { + let w = unsafe { w.pin().bits(pin.pin()) }; + #[cfg(feature = "52840")] + let w = w.port().bit(pin.port().bit()); + w.connect().connected() + } else { + w.connect().disconnected() + } + }); + + uarte.psel.rts.write(|w| { + if let Some(ref pin) = pins.rts { + let w = unsafe { w.pin().bits(pin.pin()) }; + #[cfg(feature = "52840")] + let w = w.port().bit(pin.port().bit()); + w.connect().connected() + } else { + w.connect().disconnected() + } + }); + + // Enable UARTE instance + 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)); + + // Configure frequency + uarte.baudrate.write(|w| w.baudrate().variant(baudrate)); +} + +/// Stop an unfinished UART read transaction and flush FIFO to DMA buffer +pub(crate) fn uarte_cancel_read(uarte: &T) { + uarte.events_rxto.write(|w| w); + + // Stop reception + uarte.tasks_stoprx.write(|w| unsafe { w.bits(1) }); + + // Wait for the reception to have stopped + while uarte.events_rxto.read().bits() == 0 {} + + // Reset the event flag + uarte.events_rxto.write(|w| w); + + // Ask UART to flush FIFO to DMA buffer + uarte.tasks_flushrx.write(|w| unsafe { w.bits(1) }); + + // Wait for the flush to complete. + while uarte.events_endrx.read().bits() == 0 {} + + // The event flag itself is later reset by `finalize_read`. +} + pub struct Pins { pub rxd: Pin>, pub txd: Pin>, @@ -368,9 +389,18 @@ pub enum Error { BufferNotInRAM, } -pub trait Instance: Deref {} +pub trait Instance: Deref { + #[cfg(feature = "bbq-uarte")] + const INTERRUPT: Interrupt; +} -impl Instance for UARTE0 {} +impl Instance for UARTE0 { + #[cfg(feature = "bbq-uarte")] + const INTERRUPT: Interrupt = Interrupt::UARTE0_UART0; +} #[cfg(any(feature = "52833", feature = "52840", feature = "9160"))] -impl Instance for UARTE1 {} +impl Instance for UARTE1 { + #[cfg(feature = "bbq-uarte")] + const INTERRUPT: Interrupt = Interrupt::UARTE1; +}