From e98ddd23e5c4ae49035c76c80472ab38c8b29631 Mon Sep 17 00:00:00 2001 From: Mirabellensaft Date: Tue, 14 Feb 2023 18:48:13 +0100 Subject: [PATCH] new code examples for new exercise --- down-the-stack/apps/.cargo/config.toml | 19 + down-the-stack/apps/Cargo.toml | 48 +++ down-the-stack/apps/src/bin/button.rs | 32 ++ down-the-stack/apps/src/bin/hello.rs | 28 ++ down-the-stack/apps/src/bin/uarte_print.rs | 29 ++ down-the-stack/apps/src/lib.rs | 10 + down-the-stack/dk_template/Cargo.toml | 32 ++ down-the-stack/dk_template/README.md | 7 + down-the-stack/dk_template/build.rs | 12 + down-the-stack/dk_template/memory.x | 5 + down-the-stack/dk_template/src/errata.rs | 13 + down-the-stack/dk_template/src/lib.rs | 415 +++++++++++++++++++ down-the-stack/dk_template/src/peripheral.rs | 3 + down-the-stack/dk_template/src/usbd.rs | 231 +++++++++++ 14 files changed, 884 insertions(+) create mode 100644 down-the-stack/apps/.cargo/config.toml create mode 100644 down-the-stack/apps/Cargo.toml create mode 100644 down-the-stack/apps/src/bin/button.rs create mode 100644 down-the-stack/apps/src/bin/hello.rs create mode 100644 down-the-stack/apps/src/bin/uarte_print.rs create mode 100644 down-the-stack/apps/src/lib.rs create mode 100644 down-the-stack/dk_template/Cargo.toml create mode 100644 down-the-stack/dk_template/README.md create mode 100644 down-the-stack/dk_template/build.rs create mode 100644 down-the-stack/dk_template/memory.x create mode 100644 down-the-stack/dk_template/src/errata.rs create mode 100644 down-the-stack/dk_template/src/lib.rs create mode 100644 down-the-stack/dk_template/src/peripheral.rs create mode 100644 down-the-stack/dk_template/src/usbd.rs diff --git a/down-the-stack/apps/.cargo/config.toml b/down-the-stack/apps/.cargo/config.toml new file mode 100644 index 0000000..abfd4b6 --- /dev/null +++ b/down-the-stack/apps/.cargo/config.toml @@ -0,0 +1,19 @@ +[target.'cfg(all(target_arch = "arm", target_os = "none"))'] +# (..) +rustflags = [ + "-C", "linker=flip-link", # adds stack overflow protection + "-C", "link-arg=-Tdefmt.x", # defmt support + # (..) +] + +[target.thumbv7em-none-eabihf] +# set custom cargo runner to flash & run on embedded target when we call `cargo run` +# for more information, check out https://github.com/knurling-rs/probe-run +runner = "probe-run --chip nRF52840_xxAA" +rustflags = [ + "-C", "link-arg=-Tlink.x", +] + +[build] +# cross-compile to this target +target = "thumbv7em-none-eabihf" # = ARM Cortex-M4 \ No newline at end of file diff --git a/down-the-stack/apps/Cargo.toml b/down-the-stack/apps/Cargo.toml new file mode 100644 index 0000000..701a40e --- /dev/null +++ b/down-the-stack/apps/Cargo.toml @@ -0,0 +1,48 @@ +[package] +authors = ["Tanks Transfeld "] +edition = "2018" +license = "MIT OR Apache-2.0" +name = "apps" +version = "0.0.0" + +[dependencies] +cortex-m = {version = "0.7.6", features = ["critical-section-single-core"]} +cortex-m-rt = "0.7.2" +dk_template = { path = "../dk_template" } +heapless = "0.7.16" +panic-probe = { version = "0.3.0", features = ["print-defmt"] } +defmt = "0.3.2" +defmt-rtt = "0.3.2" + +# optimize code in both profiles +[profile.dev] +codegen-units = 1 +debug = 2 +debug-assertions = true # ! +incremental = false +lto = "fat" +opt-level = 'z' # ! +overflow-checks = false + +[profile.release] +codegen-units = 1 +debug = 1 +debug-assertions = false +incremental = false +lto = "fat" +opt-level = 3 +overflow-checks = false + +[features] + +default = [ + "other-feature" +] +other-feature = [] +# do NOT modify these features +defmt-default = [] +defmt-trace = [] +defmt-debug = [] +defmt-info = [] +defmt-warn = [] +defmt-error = [] \ No newline at end of file diff --git a/down-the-stack/apps/src/bin/button.rs b/down-the-stack/apps/src/bin/button.rs new file mode 100644 index 0000000..41a3a06 --- /dev/null +++ b/down-the-stack/apps/src/bin/button.rs @@ -0,0 +1,32 @@ +#![no_main] +#![no_std] + +use cortex_m::asm; +use cortex_m_rt::entry; +use core::fmt::Write; +// this imports `beginner/apps/lib.rs` to retrieve our global logger + panicking-behavior +use apps as _; + +#[entry] +fn main() -> ! { + // to enable more verbose logs, go to your `Cargo.toml` and set defmt logging levels + // to `defmt-trace` by changing the `default = []` entry in `[features]` + + let board = dk_template::init().unwrap(); + + let mut led = board.leds; + let button_1 = board.buttons.b_1; + + loop { + if button_1.is_pushed() { + led.led_1.on(); + } else { + led.led_1.off(); + } + } + + // this program does not `exit`; use Ctrl+C to terminate it + loop { + asm::nop(); + } +} diff --git a/down-the-stack/apps/src/bin/hello.rs b/down-the-stack/apps/src/bin/hello.rs new file mode 100644 index 0000000..42b4269 --- /dev/null +++ b/down-the-stack/apps/src/bin/hello.rs @@ -0,0 +1,28 @@ +// this program does not use the standard library to avoid heap allocations. +// only the `core` library functions are available. +#![no_std] +// this program uses a custom entry point instead of `fn main()` +#![no_main] + +use cortex_m::asm; +use cortex_m_rt::entry; +// this imports `beginner/apps/lib.rs` to retrieve our global logger + panicking-behavior +use apps as _; + +// the custom entry point +// vvvvv +#[entry] +fn main() -> ! { + // ˆˆˆ + // ! is the 'never' type: this function never returns + + // initializes the peripherals + dk::init().unwrap(); + + defmt::println!("Hello, world!"); // :wave: + + loop { + // breakpoint: halts the program's execution + asm::bkpt(); + } +} diff --git a/down-the-stack/apps/src/bin/uarte_print.rs b/down-the-stack/apps/src/bin/uarte_print.rs new file mode 100644 index 0000000..b7d73a0 --- /dev/null +++ b/down-the-stack/apps/src/bin/uarte_print.rs @@ -0,0 +1,29 @@ +#![no_main] +#![no_std] + +use cortex_m::asm; +use cortex_m_rt::entry; +use core::fmt::Write; +// this imports `beginner/apps/lib.rs` to retrieve our global logger + panicking-behavior +use apps as _; + +#[entry] +fn main() -> ! { + // to enable more verbose logs, go to your `Cargo.toml` and set defmt logging levels + // to `defmt-trace` by changing the `default = []` entry in `[features]` + + let board = dk_template::init().unwrap(); + + let button_1 = board.buttons.b_1; + let mut uarte = board.uarte; + + + let tx_buffer = "Hello\n"; + + + loop { + if button_1.is_pushed() { + uarte.write_str(tx_buffer).unwrap(); + } + } +} diff --git a/down-the-stack/apps/src/lib.rs b/down-the-stack/apps/src/lib.rs new file mode 100644 index 0000000..3446a8d --- /dev/null +++ b/down-the-stack/apps/src/lib.rs @@ -0,0 +1,10 @@ +#![no_std] + +use panic_probe as _; + +// same panicking *behavior* as `panic-probe` but doesn't print a panic message +// this prevents the panic message being printed *twice* when `defmt::panic` is invoked +#[defmt::panic_handler] +fn panic() -> ! { + cortex_m::asm::udf() +} diff --git a/down-the-stack/dk_template/Cargo.toml b/down-the-stack/dk_template/Cargo.toml new file mode 100644 index 0000000..473bdca --- /dev/null +++ b/down-the-stack/dk_template/Cargo.toml @@ -0,0 +1,32 @@ +[package] +authors = ["Jorge Aparicio ", "Tanks Transfeld Result<(), Box> { + let out_dir = PathBuf::from(env::var("OUT_DIR")?); + + // put memory layout (linker script) in the linker search path + fs::copy("memory.x", out_dir.join("memory.x"))?; + + println!("cargo:rustc-link-search={}", out_dir.display()); + + Ok(()) +} diff --git a/down-the-stack/dk_template/memory.x b/down-the-stack/dk_template/memory.x new file mode 100644 index 0000000..fe81130 --- /dev/null +++ b/down-the-stack/dk_template/memory.x @@ -0,0 +1,5 @@ +MEMORY +{ + FLASH : ORIGIN = 0x00000000, LENGTH = 1024K + RAM : ORIGIN = 0x20000000, LENGTH = 256K +} diff --git a/down-the-stack/dk_template/src/errata.rs b/down-the-stack/dk_template/src/errata.rs new file mode 100644 index 0000000..cb26d96 --- /dev/null +++ b/down-the-stack/dk_template/src/errata.rs @@ -0,0 +1,13 @@ +/// USBD cannot be enabled +pub unsafe fn e187a() { + (0x4006_EC00 as *mut u32).write_volatile(0x9375); + (0x4006_ED14 as *mut u32).write_volatile(3); + (0x4006_EC00 as *mut u32).write_volatile(0x9375); +} + +/// USBD cannot be enabled +pub unsafe fn e187b() { + (0x4006_EC00 as *mut u32).write_volatile(0x9375); + (0x4006_ED14 as *mut u32).write_volatile(0); + (0x4006_EC00 as *mut u32).write_volatile(0x9375); +} diff --git a/down-the-stack/dk_template/src/lib.rs b/down-the-stack/dk_template/src/lib.rs new file mode 100644 index 0000000..1d314eb --- /dev/null +++ b/down-the-stack/dk_template/src/lib.rs @@ -0,0 +1,415 @@ +//! Hardware Abstraction Layer (HAL) for the nRF52840 Development Kit + +#![deny(missing_docs)] +#![deny(warnings)] +#![no_std] + +use core::{ + ops, + fmt, + sync::atomic::{self, AtomicU32, Ordering}, + time::Duration, +}; + +use cortex_m::{asm, peripheral::NVIC}; +use embedded_hal::digital::v2::{OutputPin as _, StatefulOutputPin}; +pub use hal::ieee802154; +pub use hal::pac::{ + interrupt, Interrupt, NVIC_PRIO_BITS, RTC0, UARTE1, uarte0::{ + baudrate::BAUDRATE_A as Baudrate, config::PARITY_A as Parity}}; +use hal::{ + clocks::{self, Clocks}, + gpio::{p0, Level, Output, Input, PullUp, Pin, Port, PushPull}, + rtc::{Rtc, RtcInterrupt}, + timer::OneShot, prelude::InputPin, +}; + +use defmt; +use defmt_rtt as _; // global logger + + +use crate::{ + peripheral::{POWER, USBD}, + usbd::Ep0In, + +}; + +mod errata; +pub mod peripheral; +pub mod usbd; + + +/// Components on the board +pub struct Board { + /// LEDs + pub leds: Leds, + /// Buttons + pub buttons: Buttons, + /// Timer + pub timer: Timer, + + /// Radio interface + pub radio: ieee802154::Radio<'static>, + /// USBD (Universal Serial Bus Device) peripheral + pub usbd: USBD, + /// POWER (Power Supply) peripheral + pub power: POWER, + /// USB control endpoint 0 + pub ep0in: Ep0In, + /// uarte interface + pub uarte: Uarte, +} + +/// All LEDs on the board +pub struct Leds { + /// LED1: pin P0.13, green LED + pub led_1: Led, + /// LED2: pin P0.14, green LED + pub led_2: Led, + /// LED3: pin P0.15, green LED + pub led_3: Led, + /// LED4: pin P0.16, green LED + pub led_4: Led, +} + +/// A single LED +pub struct Led { + inner: Pin>, +} + +impl Led { + /// Turns on the LED + pub fn on(&mut self) { + defmt::trace!( + "setting P{}.{} low (LED on)", + if self.inner.port() == Port::Port1 { + '1' + } else { + '0' + }, + self.inner.pin() + ); + + // NOTE this operations returns a `Result` but never returns the `Err` variant + let _ = self.inner.set_low(); + } + + /// Turns off the LED + pub fn off(&mut self) { + defmt::trace!( + "setting P{}.{} high (LED off)", + if self.inner.port() == Port::Port1 { + '1' + } else { + '0' + }, + self.inner.pin() + ); + + // NOTE this operations returns a `Result` but never returns the `Err` variant + let _ = self.inner.set_high(); + } + + /// Returns `true` if the LED is in the OFF state + pub fn is_off(&self) -> bool { + self.inner.is_set_high() == Ok(true) + } + + /// Returns `true` if the LED is in the ON state + pub fn is_on(&self) -> bool { + !self.is_off() + } + + /// Toggles the state (on/off) of the LED + pub fn toggle(&mut self) { + if self.is_off() { + self.on(); + } else { + self.off() + } + } +} + +/// All buttons on the board +pub struct Buttons { + /// BUTTON1: pin P0.11, green LED + pub b_1: Button, + /// BUTTON2: pin P0.12, green LED + pub b_2: Button, + /// BUTTON3: pin P0.24, green LED + pub b_3: Button, + /// BUTTON4: pin P0.25, green LED + pub b_4: Button, +} + +/// A single button +pub struct Button { + inner: Pin>, +} + +impl Button { + /// returns true if button is pushed + pub fn is_pushed(&self) -> bool { + self.inner.is_low() == Ok(true) + } +} +/// A timer for creating blocking delays +pub struct Timer { + inner: hal::Timer, +} + +impl Timer { + /// Blocks program execution for at least the specified `duration` + pub fn wait(&mut self, duration: Duration) { + defmt::trace!("blocking for {:?} ...", duration); + + // 1 cycle = 1 microsecond + const NANOS_IN_ONE_MICRO: u32 = 1_000; + let subsec_micros = duration.subsec_nanos() / NANOS_IN_ONE_MICRO; + if subsec_micros != 0 { + self.inner.delay(subsec_micros); + } + + const MICROS_IN_ONE_SEC: u32 = 1_000_000; + // maximum number of seconds that fit in a single `delay` call without overflowing the `u32` + // argument + const MAX_SECS: u32 = u32::MAX / MICROS_IN_ONE_SEC; + let mut secs = duration.as_secs(); + while secs != 0 { + let cycles = if secs > MAX_SECS as u64 { + secs -= MAX_SECS as u64; + MAX_SECS * MICROS_IN_ONE_SEC + } else { + let cycles = secs as u32 * MICROS_IN_ONE_SEC; + secs = 0; + cycles + }; + + self.inner.delay(cycles) + } + + defmt::trace!("... DONE"); + } +} + +impl ops::Deref for Timer { + type Target = hal::Timer; + + fn deref(&self) -> &Self::Target { + &self.inner + } +} + +impl ops::DerefMut for Timer { + fn deref_mut(&mut self) -> &mut Self::Target { + &mut self.inner + } +} + +/// Uarte peripheral +pub struct Uarte { + inner: hal::Uarte, +} + +impl fmt::Write for Uarte { + + 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. + let buf = &mut [0; 16][..]; + for block in s.as_bytes().chunks(16) { + buf[..block.len()].copy_from_slice(block); + self.inner.write(&buf[..block.len()]).map_err(|_| fmt::Error)?; + } + + Ok(()) + } +} + +/// Initializes the board +/// +/// This return an `Err`or if called more than once +pub fn init() -> Result { + if let Some(periph) = hal::pac::Peripherals::take() { + // NOTE(static mut) this branch runs at most once + static mut EP0IN_BUF: [u8; 64] = [0; 64]; + static mut CLOCKS: Option< + Clocks, + > = None; + + defmt::debug!("Initializing the board"); + + let clocks = Clocks::new(periph.CLOCK); + let clocks = clocks.enable_ext_hfosc(); + let clocks = clocks.set_lfclk_src_external(clocks::LfOscConfiguration::NoExternalNoBypass); + let clocks = clocks.start_lfclk(); + let _clocks = clocks.enable_ext_hfosc(); + // extend lifetime to `'static` + let clocks = unsafe { CLOCKS.get_or_insert(_clocks) }; + + defmt::debug!("Clocks configured"); + + let mut rtc = Rtc::new(periph.RTC0, 0).unwrap(); + rtc.enable_interrupt(RtcInterrupt::Overflow, None); + rtc.enable_counter(); + // NOTE(unsafe) because this crate defines the `#[interrupt] fn RTC0` interrupt handler, + // RTIC cannot manage that interrupt (trying to do so results in a linker error). Thus it + // is the task of this crate to mask/unmask the interrupt in a safe manner. + // + // Because the RTC0 interrupt handler does *not* access static variables through a critical + // section (that disables interrupts) this `unmask` operation cannot break critical sections + // and thus won't lead to undefined behavior (e.g. torn reads/writes) + // + // the preceding `enable_conuter` method consumes the `rtc` value. This is a semantic move + // of the RTC0 peripheral from this function (which can only be called at most once) to the + // interrupt handler (where the peripheral is accessed without any synchronization + // mechanism) + unsafe { NVIC::unmask(Interrupt::RTC0) }; + + defmt::debug!("RTC started"); + + let pins = p0::Parts::new(periph.P0); + + // NOTE LEDs turn on when the pin output level is low + let led_1 = pins.p0_13.degrade().into_push_pull_output(Level::High); + let led_2 = pins.p0_14.degrade().into_push_pull_output(Level::High); + let led_3 = pins.p0_15.degrade().into_push_pull_output(Level::High); + let led_4 = pins.p0_16.degrade().into_push_pull_output(Level::High); + // Buttons + let b_1 = pins.p0_11.degrade().into_pullup_input(); + let b_2 = pins.p0_12.degrade().into_pullup_input(); + let b_3 = pins.p0_24.degrade().into_pullup_input(); + let b_4 = pins.p0_25.degrade().into_pullup_input(); + + defmt::debug!("I/O pins have been configured for digital output"); + + let timer = hal::Timer::new(periph.TIMER0); + + // Uarte + let pins = hal::uarte::Pins { + rxd: pins.p0_08.degrade().into_floating_input(), + txd: pins.p0_06.degrade().into_push_pull_output(Level::High), + cts: Some(pins.p0_07.degrade().into_floating_input()), + rts: Some(pins.p0_05.degrade().into_push_pull_output(Level::High)), + }; + + + let uarte = hal::uarte::Uarte::new(periph.UARTE0, pins, Parity::INCLUDED, Baudrate::BAUD115200); + + // Radio + let radio = { + let mut radio = ieee802154::Radio::init(periph.RADIO, clocks); + + // set TX power to its maximum value + radio.set_txpower(ieee802154::TxPower::Pos8dBm); + defmt::debug!( + "Radio initialized and configured with TX power set to the maximum value" + ); + radio + }; + + Ok(Board { + leds: Leds { + led_1: Led { inner: led_1 }, + led_2: Led { inner: led_2 }, + led_3: Led { inner: led_3 }, + led_4: Led { inner: led_4 }, + }, + buttons: Buttons { + b_1: Button { inner: b_1}, + b_2: Button { inner: b_2}, + b_3: Button { inner: b_3}, + b_4: Button { inner: b_4}, + }, + + radio, + timer: Timer { inner: timer }, + usbd: periph.USBD, + power: periph.POWER, + ep0in: unsafe { Ep0In::new(&mut EP0IN_BUF) }, + uarte: Uarte { inner: uarte }, + }) + } else { + Err(()) + } +} + +// Counter of OVERFLOW events -- an OVERFLOW occurs every (1<<24) ticks +static OVERFLOWS: AtomicU32 = AtomicU32::new(0); + +// NOTE this will run at the highest priority, higher priority than RTIC tasks +#[interrupt] +fn RTC0() { + let curr = OVERFLOWS.load(Ordering::Relaxed); + OVERFLOWS.store(curr + 1, Ordering::Relaxed); + + // clear the EVENT register + unsafe { core::mem::transmute::<_, RTC0>(()).events_ovrflw.reset() } +} + +/// Exits the application when the program is executed through the `probe-run` Cargo runner +pub fn exit() -> ! { + unsafe { + // turn off the USB D+ pull-up before pausing the device with a breakpoint + // this disconnects the nRF device from the USB host so the USB host won't attempt further + // USB communication (and see an unresponsive device). probe-run will also reset the nRF's + // USBD peripheral when it sees the device in a halted state which has the same effect as + // this line but that can take a while and the USB host may issue a power cycle of the USB + // port / hub / root in the meantime, which can bring down the probe and break probe-run + const USBD_USBPULLUP: *mut u32 = 0x4002_7504 as *mut u32; + USBD_USBPULLUP.write_volatile(0) + } + defmt::println!("`dk::exit()` called; exiting ..."); + // force any pending memory operation to complete before the BKPT instruction that follows + atomic::compiler_fence(Ordering::SeqCst); + loop { + asm::bkpt() + } +} + +/// Returns the time elapsed since the call to the `dk::init` function +/// +/// The clock that is read to compute this value has a resolution of 30 microseconds. +/// +/// Calling this function before calling `dk::init` will return a value of `0` nanoseconds. +pub fn uptime() -> Duration { + // here we are going to perform a 64-bit read of the number of ticks elapsed + // + // a 64-bit load operation cannot performed in a single instruction so the operation can be + // preempted by the RTC0 interrupt handler (which increases the OVERFLOWS counter) + // + // the loop below will load both the lower and upper parts of the 64-bit value while preventing + // the issue of mixing a low value with an "old" high value -- note that, due to interrupts, an + // arbitrary amount of time may elapse between the `hi1` load and the `low` load + let overflows = &OVERFLOWS as *const AtomicU32 as *const u32; + let ticks = loop { + unsafe { + // NOTE volatile is used to order these load operations among themselves + let hi1 = overflows.read_volatile(); + let low = core::mem::transmute::<_, RTC0>(()) + .counter + .read() + .counter() + .bits(); + let hi2 = overflows.read_volatile(); + + if hi1 == hi2 { + break u64::from(low) | (u64::from(hi1) << 24); + } + } + }; + + // 2**15 ticks = 1 second + let freq = 1 << 15; + let secs = ticks / freq; + // subsec ticks + let ticks = (ticks % freq) as u32; + // one tick is equal to `1e9 / 32768` nanos + // the fraction can be reduced to `1953125 / 64` + // which can be further decomposed as `78125 * (5 / 4) * (5 / 4) * (1 / 4)`. + // Doing the operation this way we can stick to 32-bit arithmetic without overflowing the value + // at any stage + let nanos = + (((ticks % 32768).wrapping_mul(78125) >> 2).wrapping_mul(5) >> 2).wrapping_mul(5) >> 2; + Duration::new(secs, nanos as u32) +} diff --git a/down-the-stack/dk_template/src/peripheral.rs b/down-the-stack/dk_template/src/peripheral.rs new file mode 100644 index 0000000..bfec1a7 --- /dev/null +++ b/down-the-stack/dk_template/src/peripheral.rs @@ -0,0 +1,3 @@ +//! Low level access to the nRF52840 peripheral + +pub use hal::pac::{POWER, USBD}; diff --git a/down-the-stack/dk_template/src/usbd.rs b/down-the-stack/dk_template/src/usbd.rs new file mode 100644 index 0000000..ae77157 --- /dev/null +++ b/down-the-stack/dk_template/src/usbd.rs @@ -0,0 +1,231 @@ +//! USBD peripheral + +use core::sync::atomic::{self, Ordering}; + +use crate::{ + errata, + peripheral::{POWER, USBD}, +}; + +/// Endpoint IN 0 +pub struct Ep0In { + buffer: &'static mut [u8; 64], + busy: bool, +} + +impl Ep0In { + /// # Safety + /// Must be created at most once (singleton) + pub(crate) unsafe fn new(buffer: &'static mut [u8; 64]) -> Self { + Self { + buffer, + busy: false, + } + } + + /// Starts a data transfer over endpoint 0 + /// + /// # Panics + /// + /// - This function panics if the last transfer was not finished by calling the `end` function + /// - This function panics if `bytes` is larger than the maximum packet size (64 bytes) + pub fn start(&mut self, bytes: &[u8], usbd: &USBD) { + assert!(!self.busy, "EP0IN: last transfer has not completed"); + assert!( + bytes.len() <= self.buffer.len(), + "EP0IN: multi-packet data transfers are not supported" + ); + + let n = bytes.len(); + self.buffer[..n].copy_from_slice(bytes); + + // use a "shortcut" to issue a status stage after the data transfer is complete + usbd.shorts + .modify(|_, w| w.ep0datadone_ep0status().set_bit()); + usbd.epin0 + .maxcnt + .write(|w| unsafe { w.maxcnt().bits(n as u8) }); + usbd.epin0 + .ptr + .write(|w| unsafe { w.ptr().bits(self.buffer.as_ptr() as u32) }); + + self.busy = true; + + defmt::println!("EP0IN: start {}B transfer", n); + + // start DMA transfer + dma_start(); + usbd.tasks_startepin[0].write(|w| w.tasks_startepin().set_bit()); + } + + /// Completes a data transfer + /// + /// This function must be called after the EP0DATADONE event is raised + /// + /// # Panics + /// + /// This function panics if called before `start` or before the EP0DATADONE event is raised by + /// the hardware + pub fn end(&mut self, usbd: &USBD) { + if usbd.events_ep0datadone.read().bits() == 0 { + panic!("Ep0In.end called before the EP0DATADONE event was raised"); + } else { + // DMA transfer complete + dma_end(); + usbd.events_ep0datadone.reset(); + + self.busy = false; + defmt::println!("EP0IN: transfer done"); + } + } +} + +// memory barrier to synchronize the start of a DMA transfer (which will run in parallel) with the +// caller's memory operations +// +// This function call *must* be *followed* by a memory *store* operation. Memory operations that +// *precede* this function call will *not* be moved, by the compiler or the instruction pipeline, to +// *after* the function call. +fn dma_start() { + atomic::fence(Ordering::Release); +} + +// memory barrier to synchronize the end of a DMA transfer (which ran in parallel) to the caller's +// memory operations +// +// This function call *must* be *preceded* by a memory *load* operation. Memory operations that +// *follow* this function call will *not* be moved, by the compiler or the instruction pipeline, to +// *before* the function call. +fn dma_end() { + atomic::fence(Ordering::Acquire); +} + +/// Initializes the USBD peripheral +// NOTE will be called from user code; at that point the high frequency clock source has already +// been configured to use to the external crystal +// Reference: section 6.35.4 of the nRF52840 Product Specification +pub fn init(power: POWER, usbd: &USBD) { + let mut once = true; + + // wait until the USB cable has been connected + while power.events_usbdetected.read().bits() == 0 { + if once { + defmt::println!("waiting for USB connection on port J3"); + once = false; + } + + continue; + } + power.events_usbdetected.reset(); + + // workaround silicon bug + unsafe { errata::e187a() } + // enable the USB peripheral + usbd.enable.write(|w| w.enable().set_bit()); + + // wait for the peripheral to signal it has reached the READY state + while usbd.eventcause.read().ready().bit_is_clear() { + continue; + } + // write 1 to clear the flag + usbd.eventcause.write(|w| w.ready().set_bit()); + + // if EVENTCAUSE is all zeroes then also clear the USBEVENT register + if usbd.eventcause.read().bits() == 0 { + usbd.events_usbevent.reset(); + } + + // complete the silicon bug workaround + unsafe { errata::e187b() } + + // also need to wait for the USB power supply regulator to stabilize + while power.events_usbpwrrdy.read().bits() == 0 { + continue; + } + power.events_usbpwrrdy.reset(); + + // before returning unmask the relevant interrupts + usbd.intenset.write(|w| { + w.ep0datadone().set_bit(); + w.ep0setup().set_bit(); + w.usbreset().set_bit() + }); + + // enable the D+ line pull-up + usbd.usbpullup.write(|w| w.connect().set_bit()); +} + +/// Stalls endpoint 0 +pub fn ep0stall(usbd: &USBD) { + usbd.tasks_ep0stall.write(|w| w.tasks_ep0stall().set_bit()); +} + +/// USBD.EVENTS registers mapped to an enum +#[derive(Debug, defmt::Format)] +pub enum Event { + /// `EVENTS_USBRESET` register was active + UsbReset, + + /// `EVENTS_EP0DATADONE` register was active + UsbEp0DataDone, + + /// `EVENTS_EP0SETUP` register was active + UsbEp0Setup, +} + +/// Returns the next unhandled USB event; returns none if there's no event to handle +/// +/// NOTE this function will clear the corresponding the EVENT register (*) so the caller should +/// handle the returned event properly. Expect for USBEVENT and EP0DATADONE +pub fn next_event(usbd: &USBD) -> Option { + if usbd.events_usbreset.read().bits() != 0 { + usbd.events_usbreset.reset(); + + return Some(Event::UsbReset); + } + + if usbd.events_ep0datadone.read().bits() != 0 { + // this will be cleared by the `Ep0In.end` method + // usbd.events_ep0datadone.reset(); + + return Some(Event::UsbEp0DataDone); + } + + if usbd.events_ep0setup.read().bits() != 0 { + usbd.events_ep0setup.reset(); + + return Some(Event::UsbEp0Setup); + } + + None +} + +/// Reads the BMREQUESTTYPE register and returns the 8-bit BMREQUESTTYPE component of a setup packet +pub fn bmrequesttype(usbd: &USBD) -> u8 { + // read the 32-bit register and extract the least significant byte + // (the alternative is to read the 3 bitfields of the register and merge them into one byte) + usbd.bmrequesttype.read().bits() as u8 +} + +/// Reads the BREQUEST register and returns the 8-bit BREQUEST component of a setup packet +pub fn brequest(usbd: &USBD) -> u8 { + usbd.brequest.read().brequest().bits() +} + +/// Reads the WLENGTHL and WLENGTHH registers and returns the 16-bit WLENGTH component of a setup packet +pub fn wlength(usbd: &USBD) -> u16 { + u16::from(usbd.wlengthl.read().wlengthl().bits()) + | u16::from(usbd.wlengthh.read().wlengthh().bits()) << 8 +} + +/// Reads the WINDEXL and WINDEXH registers and returns the 16-bit WINDEX component of a setup packet +pub fn windex(usbd: &USBD) -> u16 { + u16::from(usbd.windexl.read().windexl().bits()) + | u16::from(usbd.windexh.read().windexh().bits()) << 8 +} + +/// Reads the WVALUEL and WVALUEH registers and returns the 16-bit WVALUE component of a setup packet +pub fn wvalue(usbd: &USBD) -> u16 { + u16::from(usbd.wvaluel.read().wvaluel().bits()) + | u16::from(usbd.wvalueh.read().wvalueh().bits()) << 8 +}