diff --git a/Cargo.toml b/Cargo.toml index 7d37ec74..25070533 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -24,6 +24,7 @@ edition = "2018" cortex-m = "0.6.3" nb = "0.1.1" stm32l4 = "0.13.0" +embedded-dma = "0.1" bxcan = ">=0.4, <0.6" [dependencies.rand_core] @@ -124,6 +125,10 @@ required-features = ["rt"] name = "rtic_frame_serial_dma" required-features = ["rt", "stm32l4x2"] +[[example]] +name = "spi_dma_rxtx" +required-features = ["rt", "stm32l4x2"] + [[example]] name = "serial_echo_rtic" required-features = ["rt", "stm32l4x3"] diff --git a/examples/lptim_rtic.rs b/examples/lptim_rtic.rs index 832de752..0d0770c4 100644 --- a/examples/lptim_rtic.rs +++ b/examples/lptim_rtic.rs @@ -71,7 +71,7 @@ const APP: () = { } #[task(binds = LPTIM1, resources = [lptim, led])] - fn timer_tick(mut ctx: timer_tick::Context) { + fn timer_tick(ctx: timer_tick::Context) { let timer_tick::Resources { lptim, led } = ctx.resources; if lptim.is_event_triggered(Event::AutoReloadMatch) { lptim.clear_event_flag(Event::AutoReloadMatch); diff --git a/examples/rtic_frame_serial_dma.rs b/examples/rtic_frame_serial_dma.rs index 05af75d0..4b06c541 100644 --- a/examples/rtic_frame_serial_dma.rs +++ b/examples/rtic_frame_serial_dma.rs @@ -12,6 +12,7 @@ use hal::{ dma::{self, DMAFrame, FrameReader, FrameSender}, + pac::USART2, prelude::*, rcc::{ClockSecuritySystem, CrystalBypass, MsiFreq}, serial::{self, Config, Serial}, @@ -23,6 +24,8 @@ use heapless::{ use panic_halt as _; use rtic::app; use stm32l4xx_hal as hal; +use stm32l4xx_hal::dma::{RxDma, TxDma}; +use stm32l4xx_hal::serial::{Rx, Tx}; // The pool gives out `Box`s that can hold 8 bytes pool!( @@ -33,9 +36,8 @@ pool!( #[app(device = stm32l4xx_hal::stm32, peripherals = true)] const APP: () = { struct Resources { - rx: serial::Rx, - frame_reader: FrameReader, dma::dma1::C6, 8>, - frame_sender: FrameSender, dma::dma1::C7, 8>, + frame_reader: FrameReader, RxDma, dma::dma1::C6>, 8>, + frame_sender: FrameSender, TxDma, dma::dma1::C7>, 8>, } #[init] @@ -88,16 +90,15 @@ const APP: () = { let fr = if let Some(dma_buf) = SerialDMAPool::alloc() { // Set up the first reader frame let dma_buf = dma_buf.init(DMAFrame::new()); - serial_rx.frame_read(dma_ch6, dma_buf) + serial_rx.with_dma(dma_ch6).frame_reader(dma_buf) } else { unreachable!() }; // Serial frame sender (DMA based) - let fs: FrameSender, _, 8> = serial_tx.frame_sender(dma_ch7); + let fs: FrameSender, _, 8> = serial_tx.with_dma(dma_ch7).frame_sender(); init::LateResources { - rx: serial_rx, frame_reader: fr, frame_sender: fs, } @@ -106,10 +107,10 @@ const APP: () = { /// This task handles the character match interrupt at required by the `FrameReader` /// /// It will echo the buffer back to the serial. - #[task(binds = USART2, resources = [rx, frame_reader, frame_sender], priority = 3)] + #[task(binds = USART2, resources = [frame_reader, frame_sender], priority = 3)] fn serial_isr(cx: serial_isr::Context) { // Check for character match - if cx.resources.rx.is_character_match(true) { + if cx.resources.frame_reader.check_character_match(true) { if let Some(dma_buf) = SerialDMAPool::alloc() { let dma_buf = dma_buf.init(DMAFrame::new()); let buf = cx.resources.frame_reader.character_match_interrupt(dma_buf); @@ -123,7 +124,7 @@ const APP: () = { /// This task handles the RX transfer complete interrupt at required by the `FrameReader` /// /// In this case we are discarding if a frame gets full as no character match was received - #[task(binds = DMA1_CH6, resources = [rx, frame_reader], priority = 3)] + #[task(binds = DMA1_CH6, resources = [frame_reader], priority = 3)] fn serial_rx_dma_isr(cx: serial_rx_dma_isr::Context) { if let Some(dma_buf) = SerialDMAPool::alloc() { let dma_buf = dma_buf.init(DMAFrame::new()); diff --git a/examples/serial_dma.rs b/examples/serial_dma.rs index 4f7bba26..e9ba8616 100644 --- a/examples/serial_dma.rs +++ b/examples/serial_dma.rs @@ -18,7 +18,7 @@ extern crate stm32l4xx_hal as hal; // #[macro_use(block)] // extern crate nb; -use crate::hal::dma::Half; +use crate::hal::dma::{CircReadDma, Half}; use crate::hal::prelude::*; use crate::hal::serial::{Config, Serial}; use crate::rt::ExceptionFrame; @@ -68,7 +68,7 @@ fn main() -> ! { let buf = singleton!(: [[u8; 8]; 2] = [[0; 8]; 2]).unwrap(); - let mut circ_buffer = rx.circ_read(channels.5, buf); + let mut circ_buffer = rx.with_dma(channels.5).circ_read(buf); for _ in 0..2 { while circ_buffer.readable_half().unwrap() != Half::First {} diff --git a/examples/serial_dma_partial_peek.rs b/examples/serial_dma_partial_peek.rs index 53b6d134..a9e5c7f5 100644 --- a/examples/serial_dma_partial_peek.rs +++ b/examples/serial_dma_partial_peek.rs @@ -20,6 +20,7 @@ extern crate stm32l4xx_hal as hal; use crate::cortex_m::asm; use crate::hal::delay::Delay; +use crate::hal::dma::CircReadDma; use crate::hal::prelude::*; use crate::hal::serial::{Config, Serial}; use crate::rt::ExceptionFrame; @@ -71,7 +72,7 @@ fn main() -> ! { let buf = singleton!(: [[u8; 8]; 2] = [[0; 8]; 2]).unwrap(); - let mut circ_buffer = rx.circ_read(channels.5, buf); + let mut circ_buffer = rx.with_dma(channels.5).circ_read(buf); // wait for 3 seconds, enter data on serial timer.delay_ms(1000_u32); diff --git a/examples/serial_dma_us2.rs b/examples/serial_dma_us2.rs index b850e78c..d067c41c 100644 --- a/examples/serial_dma_us2.rs +++ b/examples/serial_dma_us2.rs @@ -18,7 +18,7 @@ extern crate stm32l4xx_hal as hal; // #[macro_use(block)] // extern crate nb; -use crate::hal::dma::Half; +use crate::hal::dma::{CircReadDma, Half}; use crate::hal::prelude::*; use crate::hal::serial::{Config, Serial}; use crate::rt::ExceptionFrame; @@ -67,7 +67,7 @@ fn main() -> ! { let buf = singleton!(: [[u8; 8]; 2] = [[0; 8]; 2]).unwrap(); - let mut circ_buffer = rx.circ_read(channels.6, buf); + let mut circ_buffer = rx.with_dma(channels.6).circ_read(buf); for _ in 0..2 { while circ_buffer.readable_half().unwrap() != Half::First {} diff --git a/examples/spi_dma_rxtx.rs b/examples/spi_dma_rxtx.rs new file mode 100644 index 00000000..bacf8915 --- /dev/null +++ b/examples/spi_dma_rxtx.rs @@ -0,0 +1,101 @@ +//! Test the SPI in RX/TX (transfer) DMA mode +#![deny(unsafe_code)] +#![no_main] +#![no_std] + +use panic_rtt_target as _; +use rtt_target::rprintln; +use stm32l4xx_hal::{ + dma::TransferDma, + gpio::{Speed, State as PinState}, + hal::spi::{Mode, Phase, Polarity}, + prelude::*, + rcc::MsiFreq, + spi::Spi, +}; + +#[rtic::app(device = stm32l4xx_hal::pac, peripherals = true)] +const APP: () = { + #[init] + fn init(cx: init::Context) { + static mut DMA_BUF: [u8; 5] = [0xf0, 0xaa, 0x00, 0xff, 0x0f]; + + rtt_target::rtt_init_print!(); + rprintln!("Initializing... "); + + let dp = cx.device; + + let mut flash = dp.FLASH.constrain(); + let mut rcc = dp.RCC.constrain(); + let mut pwr = dp.PWR.constrain(&mut rcc.apb1r1); + let mut gpiob = dp.GPIOB.split(&mut rcc.ahb2); + let dma1_channels = dp.DMA1.split(&mut rcc.ahb1); + + // + // Initialize the clocks to 80 MHz + // + rprintln!(" - Clock init"); + let clocks = rcc + .cfgr + .msi(MsiFreq::RANGE4M) + .sysclk(80.mhz()) + .freeze(&mut flash.acr, &mut pwr); + + // + // Initialize the SPI + // + let sck = gpiob + .pb3 + .into_af5(&mut gpiob.moder, &mut gpiob.afrl) + .set_speed(Speed::High); + let miso = gpiob + .pb4 + .into_af5(&mut gpiob.moder, &mut gpiob.afrl) + .set_speed(Speed::High); + let mosi = gpiob + .pb5 + .into_af5(&mut gpiob.moder, &mut gpiob.afrl) + .set_speed(Speed::High); + let mut dummy_cs = gpiob.pb6.into_push_pull_output_with_state( + &mut gpiob.moder, + &mut gpiob.otyper, + PinState::High, + ); + let spi = Spi::spi1( + dp.SPI1, + (sck, miso, mosi), + Mode { + phase: Phase::CaptureOnFirstTransition, + polarity: Polarity::IdleLow, + }, + 100.khz(), + clocks, + &mut rcc.apb2, + ); + + // Create DMA SPI + let dma_spi = spi.with_rxtx_dma(dma1_channels.2, dma1_channels.3); + + // Check the buffer before using it + rprintln!("buf pre: 0x{:x?}", &DMA_BUF); + + // Perform transfer and wait for it to finish (blocking), this can also be done using + // interrupts on the desired DMA channel + dummy_cs.set_low().ok(); + let transfer = dma_spi.transfer(DMA_BUF); + let (buf, _dma_spi) = transfer.wait(); + dummy_cs.set_high().ok(); + + // Inspect the extracted buffer, if the MISO is connected to VCC or GND it will be all 0 or + // 1. + rprintln!("buf post: 0x{:x?}", &buf); + } + + // Idle function so RTT keeps working + #[idle] + fn idle(_cx: idle::Context) -> ! { + loop { + continue; + } + } +}; diff --git a/src/dma.rs b/src/dma.rs index fe1cc382..01579393 100644 --- a/src/dma.rs +++ b/src/dma.rs @@ -5,11 +5,13 @@ use core::fmt; use core::marker::PhantomData; use core::mem::MaybeUninit; -use core::ops::{Deref, DerefMut}; +use core::ops::DerefMut; use core::ptr; use core::slice; +use core::sync::atomic::{compiler_fence, Ordering}; use crate::rcc::AHB1; +use embedded_dma::{StaticReadBuffer, StaticWriteBuffer}; use stable_deref_trait::StableDeref; #[non_exhaustive] @@ -30,51 +32,69 @@ pub enum Half { Second, } +pub trait CharacterMatch { + /// Checks to see if the peripheral has detected a character match and + /// clears the flag + fn check_character_match(&mut self, clear: bool) -> bool; +} + /// Frame reader "worker", access and handling of frame reads is made through this structure. -pub struct FrameReader +pub struct FrameReader where BUFFER: Sized + StableDeref> + DerefMut + 'static, { buffer: BUFFER, - channel: CHANNEL, + payload: PAYLOAD, matching_character: u8, } -impl FrameReader +impl FrameReader where BUFFER: Sized + StableDeref> + DerefMut + 'static, { pub(crate) fn new( buffer: BUFFER, - channel: CHANNEL, + payload: PAYLOAD, matching_character: u8, - ) -> FrameReader { + ) -> FrameReader { Self { buffer, - channel, + payload, matching_character, } } } +impl FrameReader, N> +where + BUFFER: Sized + StableDeref> + DerefMut + 'static, + PAYLOAD: CharacterMatch, +{ + /// Checks to see if the peripheral has detected a character match and + /// clears the flag + pub fn check_character_match(&mut self, clear: bool) -> bool { + self.payload.payload.check_character_match(clear) + } +} + /// Frame sender "worker", access and handling of frame transmissions is made through this /// structure. -pub struct FrameSender +pub struct FrameSender where BUFFER: Sized + StableDeref> + DerefMut + 'static, { buffer: Option, - channel: CHANNEL, + payload: PAYLOAD, } -impl FrameSender +impl FrameSender where BUFFER: Sized + StableDeref> + DerefMut + 'static, { - pub(crate) fn new(channel: CHANNEL) -> FrameSender { + pub(crate) fn new(payload: PAYLOAD) -> FrameSender { Self { buffer: None, - channel, + payload, } } } @@ -260,24 +280,25 @@ impl AsRef<[u8]> for DMAFrame { } } -pub struct CircBuffer +pub struct CircBuffer where BUFFER: 'static, { - buffer: BUFFER, - channel: CHANNEL, + buffer: &'static mut [BUFFER; 2], + payload: PAYLOAD, readable_half: Half, consumed_offset: usize, } -impl CircBuffer { - pub(crate) fn new(buf: BUFFER, chan: CHANNEL) -> Self - where - BUFFER: StableDeref + 'static, - { +impl CircBuffer +where + &'static mut [BUFFER; 2]: StaticWriteBuffer, + BUFFER: 'static, +{ + pub(crate) fn new(buf: &'static mut [BUFFER; 2], payload: PAYLOAD) -> Self { CircBuffer { buffer: buf, - channel: chan, + payload, readable_half: Half::Second, consumed_offset: 0, } @@ -290,46 +311,88 @@ pub trait DmaExt { fn split(self, ahb: &mut AHB1) -> Self::Channels; } -pub struct Transfer { +pub trait TransferPayload { + fn start(&mut self); + fn stop(&mut self); +} + +pub struct Transfer +where + PAYLOAD: TransferPayload, +{ _mode: PhantomData, buffer: BUFFER, - channel: CHANNEL, payload: PAYLOAD, } -impl Transfer +impl Transfer where - BUFFER: StableDeref + 'static, + PAYLOAD: TransferPayload, { - pub(crate) fn r(buffer: BUFFER, channel: CHANNEL, payload: PAYLOAD) -> Self { + pub(crate) fn r(buffer: BUFFER, payload: PAYLOAD) -> Self { Transfer { _mode: PhantomData, buffer, - channel, payload, } } } -impl Transfer +impl Transfer where - BUFFER: StableDeref + 'static, + PAYLOAD: TransferPayload, { - pub(crate) fn w(buffer: BUFFER, channel: CHANNEL, payload: PAYLOAD) -> Self { + pub(crate) fn w(buffer: BUFFER, payload: PAYLOAD) -> Self { Transfer { _mode: PhantomData, buffer, - channel, payload, } } } -impl Deref for Transfer { - type Target = BUFFER; +impl Transfer +where + PAYLOAD: TransferPayload, +{ + pub(crate) fn rw(buffer: BUFFER, payload: PAYLOAD) -> Self { + Transfer { + _mode: PhantomData, + buffer, + payload, + } + } +} - fn deref(&self) -> &BUFFER { - &self.buffer +impl Drop for Transfer +where + PAYLOAD: TransferPayload, +{ + fn drop(&mut self) { + self.payload.stop(); + compiler_fence(Ordering::SeqCst); + } +} + +impl Transfer +where + PAYLOAD: TransferPayload, +{ + pub(crate) fn extract_inner_without_drop(self) -> (BUFFER, PAYLOAD) { + // `Transfer` needs to have a `Drop` implementation, because we accept + // managed buffers that can free their memory on drop. Because of that + // we can't move out of the `Transfer`'s fields, so we use `ptr::read` + // and `mem::forget`. + // + // NOTE(unsafe) There is no panic branch between getting the resources + // and forgetting `self`. + unsafe { + // We cannot use mem::replace as we do not have valid objects to replace with + let buffer = ptr::read(&self.buffer); + let payload = ptr::read(&self.payload); + core::mem::forget(self); + (buffer, payload) + } } } @@ -339,6 +402,77 @@ pub struct R; /// Write transfer pub struct W; +/// Read/Write transfer +pub struct RW; + +macro_rules! for_all_pairs { + ($mac:ident: $($x:ident)*) => { + // Duplicate the list + for_all_pairs!(@inner $mac: $($x)*; $($x)*); + }; + + // The end of iteration: we exhausted the list + (@inner $mac:ident: ; $($x:ident)*) => {}; + + // The head/tail recursion: pick the first element of the first list + // and recursively do it for the tail. + (@inner $mac:ident: $head:ident $($tail:ident)*; $($x:ident)*) => { + $( + $mac!($head $x); + )* + for_all_pairs!(@inner $mac: $($tail)*; $($x)*); + }; +} + +macro_rules! rx_tx_channel_mapping { + ($CH_A:ident $CH_B:ident) => { + impl Transfer> + where + RxTxDma: TransferPayload, + { + pub fn is_done(&self) -> bool { + !self.payload.rx_channel.in_progress() && !self.payload.tx_channel.in_progress() + } + + pub fn wait(mut self) -> (BUFFER, RxTxDma) { + // XXX should we check for transfer errors here? + // The manual says "A DMA transfer error can be generated by reading + // from or writing to a reserved address space". I think it's impossible + // to get to that state with our type safe API and *safe* Rust. + while !self.is_done() {} + + self.payload.stop(); + + // TODO can we weaken this compiler barrier? + // NOTE(compiler_fence) operations on `buffer` should not be reordered + // before the previous statement, which marks the DMA transfer as done + atomic::compiler_fence(Ordering::SeqCst); + + // `Transfer` has a `Drop` implementation because we accept + // managed buffers that can free their memory on drop. Because of that + // we can't move out of the `Transfer`'s fields directly. + self.extract_inner_without_drop() + } + } + + impl Transfer> + where + RxTxDma: TransferPayload, + { + pub fn peek(&self) -> &[T] + where + BUFFER: AsRef<[T]>, + { + let pending = self.payload.rx_channel.get_cndtr() as usize; + + let capacity = self.buffer.as_ref().len(); + + &self.buffer.as_ref()[..(capacity - pending)] + } + } + }; +} + macro_rules! dma { ($($DMAX:ident: ($dmaX:ident, $dmaXen:ident, $dmaXrst:ident, { $($CX:ident: ( @@ -367,13 +501,18 @@ macro_rules! dma { use core::ptr; use stable_deref_trait::StableDeref; - use crate::dma::{CircBuffer, FrameReader, FrameSender, DMAFrame, DmaExt, Error, Event, Half, Transfer, W}; + use crate::dma::{CircBuffer, FrameReader, FrameSender, DMAFrame, DmaExt, Error, Event, Half, Transfer, W, R, RW, RxDma, RxTxDma, TxDma, TransferPayload}; use crate::rcc::AHB1; #[allow(clippy::manual_non_exhaustive)] pub struct Channels((), $(pub $CX),+); + for_all_pairs!(rx_tx_channel_mapping: $($CX)+); + $( + /// A singleton that represents a single DMAx channel (channel X in this case) + /// + /// This singleton has exclusive access to the registers of the DMAx channel X pub struct $CX; impl $CX { @@ -490,9 +629,10 @@ macro_rules! dma { } - impl FrameSender + impl FrameSender, N> where BUFFER: Sized + StableDeref> + DerefMut + 'static, + TxDma: TransferPayload, { /// This method should be called in the transfer complete interrupt of the /// DMA, will return the sent frame if the transfer was truly completed. @@ -501,14 +641,14 @@ macro_rules! dma { ) -> Option { // Clear ISR flag (Transfer Complete) - if !self.channel.in_progress() { - self.channel.ifcr().write(|w| w.$ctcifX().set_bit()); + if !self.payload.channel.in_progress() { + self.payload.channel.ifcr().write(|w| w.$ctcifX().set_bit()); } else { // The old transfer is not complete return None; } - self.channel.stop(); + self.payload.channel.stop(); // NOTE(compiler_fence) operations on the DMA should not be reordered // before the next statement, takes the buffer from the DMA transfer. @@ -536,20 +676,20 @@ macro_rules! dma { } let new_buf = &*frame; - self.channel.set_memory_address(new_buf.buffer_as_ptr() as u32, true); - self.channel.set_transfer_length(new_buf.len() as u16); + self.payload.channel.set_memory_address(new_buf.buffer_as_ptr() as u32, true); + self.payload.channel.set_transfer_length(new_buf.len() as u16); // If there has been an error, clear the error flag to let the next // transaction start - if self.channel.isr().$teifX().bit_is_set() { - self.channel.ifcr().write(|w| w.$cteifX().set_bit()); + if self.payload.channel.isr().$teifX().bit_is_set() { + self.payload.channel.ifcr().write(|w| w.$cteifX().set_bit()); } // NOTE(compiler_fence) operations on `buffer` should not be reordered after // the next statement, which starts the DMA transfer atomic::compiler_fence(Ordering::Release); - self.channel.start(); + self.payload.channel.start(); self.buffer = Some(frame); @@ -557,9 +697,10 @@ macro_rules! dma { } } - impl FrameReader + impl FrameReader, N> where BUFFER: Sized + StableDeref> + DerefMut + 'static, + RxDma: TransferPayload, { /// This function should be called from the transfer complete interrupt of /// the corresponding DMA channel. @@ -599,18 +740,18 @@ macro_rules! dma { new_buf.clear(); // Clear ISR flag (Transfer Complete) - if !self.channel.in_progress() { - self.channel.ifcr().write(|w| w.$ctcifX().set_bit()); + if !self.payload.channel.in_progress() { + self.payload.channel.ifcr().write(|w| w.$ctcifX().set_bit()); } else if character_match_interrupt { // 1. If DMA not done and there was a character match interrupt, // let the DMA flush a little and then halt transfer. // // This is to alleviate the race condition between the character // match interrupt and the DMA memory transfer. - let left_in_buffer = self.channel.get_cndtr() as usize; + let left_in_buffer = self.payload.channel.get_cndtr() as usize; for _ in 0..5 { - let now_left = self.channel.get_cndtr() as usize; + let now_left = self.payload.channel.get_cndtr() as usize; if left_in_buffer - now_left >= 4 { // We have gotten 4 extra characters flushed @@ -619,13 +760,13 @@ macro_rules! dma { } } - self.channel.stop(); + self.payload.channel.stop(); // NOTE(compiler_fence) operations on `buffer` should not be reordered after // the next statement, which starts a new DMA transfer atomic::compiler_fence(Ordering::SeqCst); - let left_in_buffer = self.channel.get_cndtr() as usize; + let left_in_buffer = self.payload.channel.get_cndtr() as usize; let got_data_len = old_buf.max_len() - left_in_buffer; // How many bytes we got unsafe { old_buf.set_len(got_data_len); @@ -667,29 +808,31 @@ macro_rules! dma { 0 }; - self.channel.set_memory_address(unsafe { new_buf.buffer_as_ptr().add(diff) } as u32, true); - self.channel.set_transfer_length((new_buf.max_len() - diff) as u16); + self.payload.channel.set_memory_address(unsafe { new_buf.buffer_as_ptr().add(diff) } as u32, true); + self.payload.channel.set_transfer_length((new_buf.max_len() - diff) as u16); let received_buffer = core::mem::replace(&mut self.buffer, next_frame); // NOTE(compiler_fence) operations on `buffer` should not be reordered after // the next statement, which starts the DMA transfer atomic::compiler_fence(Ordering::Release); - self.channel.start(); + self.payload.channel.start(); // 4. Return full frame received_buffer } } - impl CircBuffer { + impl CircBuffer> + where + RxDma: TransferPayload, + { /// Return the partial contents of the buffer half being written - pub fn partial_peek(&mut self, f: F) -> Result + pub fn partial_peek(&mut self, f: F) -> Result where F: FnOnce(&[T], Half) -> Result<(usize, R), ()>, - B: StableDeref + 'static, - H: AsRef<[T]>, + B: AsRef<[T]>, { // this inverts expectation and returns the half being _written_ let buf = match self.readable_half { @@ -699,7 +842,7 @@ macro_rules! dma { // ,- half-buffer // [ x x x x y y y y y z | z z z z z z z z z z ] // ^- pending=11 - let pending = self.channel.get_cndtr() as usize; // available bytes in _whole_ buffer + let pending = self.payload.channel.get_cndtr() as usize; // available bytes in _whole_ buffer let slice = buf.as_ref(); let capacity = slice.len(); // capacity of _half_ a buffer // <--- capacity=10 ---> @@ -726,11 +869,10 @@ macro_rules! dma { /// Peeks into the readable half of the buffer /// Returns the result of the closure - pub fn peek(&mut self, f: F) -> Result + pub fn peek(&mut self, f: F) -> Result where F: FnOnce(&[T], Half) -> R, - B: StableDeref + 'static, - H: AsRef<[T]>, + B: AsRef<[T]>, { let half_being_read = self.readable_half()?; let buf = match half_being_read { @@ -744,7 +886,7 @@ macro_rules! dma { /// Returns the `Half` of the buffer that can be read pub fn readable_half(&mut self) -> Result { - let isr = self.channel.isr(); + let isr = self.payload.channel.isr(); let first_half_is_done = isr.$htifX().bit_is_set(); let second_half_is_done = isr.$tcifX().bit_is_set(); @@ -757,7 +899,7 @@ macro_rules! dma { Ok(match last_read_half { Half::First => { if second_half_is_done { - self.channel.ifcr().write(|w| w.$ctcifX().set_bit()); + self.payload.channel.ifcr().write(|w| w.$ctcifX().set_bit()); self.readable_half = Half::Second; Half::Second @@ -767,7 +909,7 @@ macro_rules! dma { } Half::Second => { if first_half_is_done { - self.channel.ifcr().write(|w| w.$chtifX().set_bit()); + self.payload.channel.ifcr().write(|w| w.$chtifX().set_bit()); self.readable_half = Half::First; Half::First @@ -777,39 +919,98 @@ macro_rules! dma { } }) } + + /// Stops the transfer and returns the underlying buffer and RxDma + pub fn stop(mut self) -> (&'static mut [B; 2], RxDma) { + self.payload.stop(); + + (self.buffer, self.payload) + } } - impl Transfer { + impl Transfer> + where + RxDma: TransferPayload, + { pub fn is_done(&self) -> bool { - self.channel.isr().$tcifX().bit_is_set() + !self.payload.channel.in_progress() } - pub fn wait(mut self) -> (BUFFER, $CX, PAYLOAD) { + pub fn wait(mut self) -> (BUFFER, RxDma) { // XXX should we check for transfer errors here? // The manual says "A DMA transfer error can be generated by reading // from or writing to a reserved address space". I think it's impossible // to get to that state with our type safe API and *safe* Rust. while !self.is_done() {} - self.channel.ifcr().write(|w| w.$cgifX().set_bit()); + self.payload.stop(); + + // TODO can we weaken this compiler barrier? + // NOTE(compiler_fence) operations on `buffer` should not be reordered + // before the previous statement, which marks the DMA transfer as done + atomic::compiler_fence(Ordering::SeqCst); + + // `Transfer` has a `Drop` implementation because we accept + // managed buffers that can free their memory on drop. Because of that + // we can't move out of the `Transfer`'s fields directly. + self.extract_inner_without_drop() + } + } + + impl Transfer> + where + TxDma: TransferPayload, + { + pub fn is_done(&self) -> bool { + !self.payload.channel.in_progress() + } + + pub fn wait(mut self) -> (BUFFER, TxDma) { + // XXX should we check for transfer errors here? + // The manual says "A DMA transfer error can be generated by reading + // from or writing to a reserved address space". I think it's impossible + // to get to that state with our type safe API and *safe* Rust. + while !self.is_done() {} - self.channel.ccr().modify(|_, w| w.en().clear_bit()); + self.payload.stop(); // TODO can we weaken this compiler barrier? // NOTE(compiler_fence) operations on `buffer` should not be reordered // before the previous statement, which marks the DMA transfer as done atomic::compiler_fence(Ordering::SeqCst); - (self.buffer, self.channel, self.payload) + // `Transfer` has a `Drop` implementation because we accept + // managed buffers that can free their memory on drop. Because of that + // we can't move out of the `Transfer`'s fields directly. + self.extract_inner_without_drop() + } + } + + impl Transfer> + where + RxDma: TransferPayload, + { + pub fn peek(&self) -> &[T] + where + BUFFER: AsRef<[T]>, + { + let pending = self.payload.channel.get_cndtr() as usize; + + let capacity = self.buffer.as_ref().len(); + + &self.buffer.as_ref()[..(capacity - pending)] } } - impl Transfer { + impl Transfer> + where + TxDma: TransferPayload, + { pub fn peek(&self) -> &[T] where BUFFER: AsRef<[T]> { - let pending = self.channel.get_cndtr() as usize; + let pending = self.payload.channel.get_cndtr() as usize; let capacity = self.buffer.as_ref().len(); @@ -969,3 +1170,75 @@ dma! { ), }), } + +/// DMA Receiver +pub struct RxDma { + pub(crate) payload: PAYLOAD, + pub channel: RXCH, +} + +/// DMA Transmitter +pub struct TxDma { + pub(crate) payload: PAYLOAD, + pub channel: TXCH, +} + +/// DMA Receiver/Transmitter +pub struct RxTxDma { + pub(crate) payload: PAYLOAD, + pub rx_channel: RXCH, + pub tx_channel: TXCH, +} + +pub trait Receive { + type RxChannel; + type TransmittedWord; +} + +pub trait Transmit { + type TxChannel; + type ReceivedWord; +} + +pub trait ReceiveTransmit { + type RxChannel; + type TxChannel; + type TransferedWord; +} + +/// Trait for circular DMA readings from peripheral to memory. +pub trait CircReadDma: Receive +where + &'static mut [B; 2]: StaticWriteBuffer, + B: 'static, + Self: core::marker::Sized, +{ + fn circ_read(self, buffer: &'static mut [B; 2]) -> CircBuffer; +} + +/// Trait for DMA readings from peripheral to memory. +pub trait ReadDma: Receive +where + B: StaticWriteBuffer, + Self: core::marker::Sized + TransferPayload, +{ + fn read(self, buffer: B) -> Transfer; +} + +/// Trait for DMA writing from memory to peripheral. +pub trait WriteDma: Transmit +where + B: StaticReadBuffer, + Self: core::marker::Sized + TransferPayload, +{ + fn write(self, buffer: B) -> Transfer; +} + +/// Trait for DMA simultaneously writing and reading between memory and peripheral. +pub trait TransferDma: ReceiveTransmit +where + B: StaticWriteBuffer, + Self: core::marker::Sized + TransferPayload, +{ + fn transfer(self, buffer: B) -> Transfer; +} diff --git a/src/serial.rs b/src/serial.rs index 4bb0a43f..c881bb0e 100644 --- a/src/serial.rs +++ b/src/serial.rs @@ -7,11 +7,15 @@ use core::marker::PhantomData; use core::ops::DerefMut; use core::ptr; use core::sync::atomic::{self, Ordering}; +use embedded_dma::StaticWriteBuffer; use stable_deref_trait::StableDeref; use crate::hal::serial::{self, Write}; -use crate::dma::{dma1, CircBuffer, DMAFrame, FrameReader, FrameSender}; +use crate::dma::{ + dma1, CircBuffer, DMAFrame, FrameReader, FrameSender, Receive, RxDma, TransferPayload, + Transmit, TxDma, +}; use crate::gpio::{self, Alternate, AlternateOD, Floating, Input}; use crate::pac; use crate::rcc::{Clocks, APB1R1, APB2}; @@ -196,8 +200,8 @@ macro_rules! hal { $usartXen:ident, $usartXrst:ident, $pclkX:ident, - tx: ($dmacst:ident, $tx_chan:path), - rx: ($dmacsr:ident, $rx_chan:path) + tx: ($txdma:ident, $dmacst:ident, $dmatxch:path), + rx: ($rxdma:ident, $dmacsr:ident, $dmarxch:path) ), )+) => { $( @@ -501,100 +505,75 @@ macro_rules! hal { impl embedded_hal::blocking::serial::write::Default for Tx {} - impl Rx { - pub fn circ_read( - &self, - mut chan: $rx_chan, - mut buffer: B, - ) -> CircBuffer - where - B: StableDeref + DerefMut + 'static, - H: AsMut<[u8]> - { - let buf = buffer[0].as_mut(); - chan.set_peripheral_address(unsafe{ &(*pac::$USARTX::ptr()).rdr as *const _ as u32 }, false); - chan.set_memory_address(buf.as_ptr() as u32, true); - chan.set_transfer_length((buf.len() * 2) as u16); + pub type $rxdma = RxDma, $dmarxch>; + pub type $txdma = TxDma, $dmatxch>; - // Tell DMA to request from serial - chan.cselr().modify(|_, w| { - w.$dmacsr().bits(0b0010) // TODO: Fix this, not valid for DMA2 - }); - - chan.ccr().modify(|_, w| unsafe { - w.mem2mem() - .clear_bit() - // 00: Low, 01: Medium, 10: High, 11: Very high - .pl() - .bits(0b01) - // 00: 8-bits, 01: 16-bits, 10: 32-bits, 11: Reserved - .msize() - .bits(0b00) - // 00: 8-bits, 01: 16-bits, 10: 32-bits, 11: Reserved - .psize() - .bits(0b00) - .circ() - .set_bit() - .dir() - .clear_bit() - }); - - // NOTE(compiler_fence) operations on `buffer` should not be reordered after - // the next statement, which starts the DMA transfer - atomic::compiler_fence(Ordering::Release); + impl Receive for $rxdma { + type RxChannel = $dmarxch; + type TransmittedWord = u8; + } - chan.start(); + impl Transmit for $txdma { + type TxChannel = $dmatxch; + type ReceivedWord = u8; + } - CircBuffer::new(buffer, chan) + impl TransferPayload for $rxdma { + fn start(&mut self) { + self.channel.start(); } + fn stop(&mut self) { + self.channel.stop(); + } + } - /// Create a frame reader that can either react on the Character match interrupt or - /// Transfer Complete from the DMA. - pub fn frame_read( - &self, - mut channel: $rx_chan, - buffer: BUFFER, - ) -> FrameReader - where - BUFFER: Sized + StableDeref> + DerefMut + 'static, - { - let usart = unsafe{ &(*pac::$USARTX::ptr()) }; - - // Setup DMA transfer - let buf = &*buffer; - channel.set_peripheral_address(&usart.rdr as *const _ as u32, false); - channel.set_memory_address(unsafe { buf.buffer_address_for_dma() } as u32, true); - channel.set_transfer_length(buf.max_len() as u16); - - // Tell DMA to request from serial - channel.cselr().modify(|_, w| { - w.$dmacsr().bits(0b0010) // TODO: Fix this, not valid for DMA2 - }); + impl TransferPayload for $txdma { + fn start(&mut self) { + self.channel.start(); + } + fn stop(&mut self) { + self.channel.stop(); + } + } - channel.ccr().modify(|_, w| unsafe { - w.mem2mem() - .clear_bit() - // 00: Low, 01: Medium, 10: High, 11: Very high - .pl() - .bits(0b01) - // 00: 8-bits, 01: 16-bits, 10: 32-bits, 11: Reserved - .msize() - .bits(0b00) - // 00: 8-bits, 01: 16-bits, 10: 32-bits, 11: Reserved - .psize() - .bits(0b00) - // Peripheral -> Mem - .dir() - .clear_bit() - }); + impl Rx { + pub fn with_dma(self, channel: $dmarxch) -> $rxdma { + RxDma { + payload: self, + channel, + } + } - // NOTE(compiler_fence) operations on `buffer` should not be reordered after - // the next statement, which starts the DMA transfer - atomic::compiler_fence(Ordering::Release); + /// Check for, and return, any errors + /// + /// The `read` methods can only return one error at a time, but + /// there might actually be multiple errors. This method will + /// return and clear a currently active error. Once it returns + /// `Ok(())`, it should be possible to proceed with the next + /// `read` call unimpeded. + pub fn check_for_error(&mut self) -> Result<(), Error> { + // NOTE(unsafe): Only used for atomic access. + let isr = unsafe { (*pac::$USARTX::ptr()).isr.read() }; + let icr = unsafe { &(*pac::$USARTX::ptr()).icr }; - channel.start(); + if isr.pe().bit_is_set() { + icr.write(|w| w.pecf().clear()); + return Err(Error::Parity); + } + if isr.fe().bit_is_set() { + icr.write(|w| w.fecf().clear()); + return Err(Error::Framing); + } + if isr.nf().bit_is_set() { + icr.write(|w| w.ncf().clear()); + return Err(Error::Noise); + } + if isr.ore().bit_is_set() { + icr.write(|w| w.orecf().clear()); + return Err(Error::Overrun); + } - FrameReader::new(buffer, channel, usart.cr2.read().add().bits()) + Ok(()) } /// Checks to see if the USART peripheral has detected an idle line and clears @@ -613,15 +592,16 @@ macro_rules! hal { } } - /// Checks to see if the USART peripheral has detected an character match and + + /// Checks to see if the USART peripheral has detected an receiver timeout and /// clears the flag - pub fn is_character_match(&mut self, clear: bool) -> bool { + pub fn is_receiver_timeout(&mut self, clear: bool) -> bool { let isr = unsafe { &(*pac::$USARTX::ptr()).isr.read() }; let icr = unsafe { &(*pac::$USARTX::ptr()).icr }; - if isr.cmf().bit_is_set() { + if isr.rtof().bit_is_set() { if clear { - icr.write(|w| w.cmcf().set_bit() ); + icr.write(|w| w.rtocf().set_bit() ); } true } else { @@ -629,75 +609,187 @@ macro_rules! hal { } } - /// Checks to see if the USART peripheral has detected an receiver timeout and + /// Checks to see if the USART peripheral has detected an character match and /// clears the flag - pub fn is_receiver_timeout(&mut self, clear: bool) -> bool { + pub fn check_character_match(&mut self, clear: bool) -> bool { let isr = unsafe { &(*pac::$USARTX::ptr()).isr.read() }; let icr = unsafe { &(*pac::$USARTX::ptr()).icr }; - if isr.rtof().bit_is_set() { + if isr.cmf().bit_is_set() { if clear { - icr.write(|w| w.rtocf().set_bit() ); + icr.write(|w| w.cmcf().set_bit() ); } true } else { false } } + } - /// Check for, and return, any errors - /// - /// The `read` methods can only return one error at a time, but - /// there might actually be multiple errors. This method will - /// return and clear a currently active error. Once it returns - /// `Ok(())`, it should be possible to proceed with the next - /// `read` call unimpeded. - pub fn check_for_error(&mut self) -> Result<(), Error> { - // NOTE(unsafe): Only used for atomic access. - let isr = unsafe { (*pac::$USARTX::ptr()).isr.read() }; - let icr = unsafe { &(*pac::$USARTX::ptr()).icr }; + impl crate::dma::CharacterMatch for Rx { + /// Checks to see if the USART peripheral has detected an character match and + /// clears the flag + fn check_character_match(&mut self, clear: bool) -> bool { + self.check_character_match(clear) + } + } - if isr.pe().bit_is_set() { - icr.write(|w| w.pecf().clear()); - return Err(Error::Parity); - } - if isr.fe().bit_is_set() { - icr.write(|w| w.fecf().clear()); - return Err(Error::Framing); - } - if isr.nf().bit_is_set() { - icr.write(|w| w.ncf().clear()); - return Err(Error::Noise); - } - if isr.ore().bit_is_set() { - icr.write(|w| w.orecf().clear()); - return Err(Error::Overrun); + impl Tx { + pub fn with_dma(self, channel: $dmatxch) -> $txdma { + TxDma { + payload: self, + channel, } + } + } - Ok(()) + impl $rxdma { + pub fn split(mut self) -> (Rx, $dmarxch) { + self.stop(); + let RxDma {payload, channel} = self; + ( + payload, + channel + ) } } - impl Tx { + impl $txdma { + pub fn split(mut self) -> (Tx, $dmatxch) { + self.stop(); + let TxDma {payload, channel} = self; + ( + payload, + channel, + ) + } + } + + impl crate::dma::CircReadDma for $rxdma + where + &'static mut [B; 2]: StaticWriteBuffer, + B: 'static, + Self: core::marker::Sized, + { + fn circ_read(mut self, mut buffer: &'static mut [B; 2], + ) -> CircBuffer + { + let (ptr, len) = unsafe { buffer.static_write_buffer() }; + self.channel.set_peripheral_address( + unsafe { &(*pac::$USARTX::ptr()).rdr as *const _ as u32 }, + false, + ); + self.channel.set_memory_address(ptr as u32, true); + self.channel.set_transfer_length(len as u16); + + // Tell DMA to request from serial + self.channel.cselr().modify(|_, w| { + w.$dmacsr().map2() + }); + + self.channel.ccr().modify(|_, w| { + w + // memory to memory mode disabled + .mem2mem() + .clear_bit() + // medium channel priority level + .pl() + .medium() + // 8-bit memory size + .msize() + .bits8() + // 8-bit peripheral size + .psize() + .bits8() + // circular mode disabled + .circ() + .set_bit() + // write to memory + .dir() + .clear_bit() + }); + + // NOTE(compiler_fence) operations on `buffer` should not be reordered after + // the next statement, which starts the DMA transfer + atomic::compiler_fence(Ordering::Release); + + self.start(); + + CircBuffer::new(buffer, self) + } + } + + impl $rxdma { + /// Create a frame reader that can either react on the Character match interrupt or + /// Transfer Complete from the DMA. + pub fn frame_reader( + mut self, + buffer: BUFFER, + ) -> FrameReader + where + BUFFER: Sized + StableDeref> + DerefMut + 'static, + { + let usart = unsafe{ &(*pac::$USARTX::ptr()) }; + + // Setup DMA transfer + let buf = &*buffer; + self.channel.set_peripheral_address(&usart.rdr as *const _ as u32, false); + self.channel.set_memory_address(unsafe { buf.buffer_address_for_dma() } as u32, true); + self.channel.set_transfer_length(buf.max_len() as u16); + + // Tell DMA to request from serial + self.channel.cselr().modify(|_, w| { + w.$dmacsr().map2() + }); + + self.channel.ccr().modify(|_, w| { + w + // memory to memory mode disabled + .mem2mem() + .clear_bit() + // medium channel priority level + .pl() + .medium() + // 8-bit memory size + .msize() + .bits8() + // 8-bit peripheral size + .psize() + .bits8() + // Peripheral -> Mem + .dir() + .clear_bit() + }); + + // NOTE(compiler_fence) operations on `buffer` should not be reordered after + // the next statement, which starts the DMA transfer + atomic::compiler_fence(Ordering::Release); + + self.channel.start(); + + FrameReader::new(buffer, self, usart.cr2.read().add().bits()) + } + } + + impl $txdma { /// Creates a new DMA frame sender pub fn frame_sender( - &self, - mut channel: $tx_chan, - ) -> FrameSender + mut self, + ) -> FrameSender where BUFFER: Sized + StableDeref> + DerefMut + 'static, { let usart = unsafe{ &(*pac::$USARTX::ptr()) }; // Setup DMA - channel.set_peripheral_address(&usart.tdr as *const _ as u32, false); + self.channel.set_peripheral_address(&usart.tdr as *const _ as u32, false); // Tell DMA to request from serial - channel.cselr().modify(|_, w| { - w.$dmacst().bits(0b0010) // TODO: Fix this, not valid for DMA2 + self.channel.cselr().modify(|_, w| { + w.$dmacst().map2() }); - channel.ccr().modify(|_, w| unsafe { + self.channel.ccr().modify(|_, w| unsafe { w.mem2mem() .clear_bit() // 00: Low, 01: Medium, 10: High, 11: Very high @@ -714,7 +806,7 @@ macro_rules! hal { .set_bit() }); - FrameSender::new(channel) + FrameSender::new(self) } } )+ @@ -722,8 +814,8 @@ macro_rules! hal { } hal! { - USART1: (usart1, APB2, usart1en, usart1rst, pclk2, tx: (c4s, dma1::C4), rx: (c5s, dma1::C5)), - USART2: (usart2, APB1R1, usart2en, usart2rst, pclk1, tx: (c7s, dma1::C7), rx: (c6s, dma1::C6)), + USART1: (usart1, APB2, usart1en, usart1rst, pclk2, tx: (TxDma1, c4s, dma1::C4), rx: (RxDma1, c5s, dma1::C5)), + USART2: (usart2, APB1R1, usart2en, usart2rst, pclk1, tx: (TxDma2, c7s, dma1::C7), rx: (RxDma2, c6s, dma1::C6)), } #[cfg(any( @@ -733,17 +825,17 @@ hal! { feature = "stm32l4x6", ))] hal! { - USART3: (usart3, APB1R1, usart3en, usart3rst, pclk1, tx: (c2s, dma1::C2), rx: (c3s, dma1::C3)), + USART3: (usart3, APB1R1, usart3en, usart3rst, pclk1, tx: (TxDma3, c2s, dma1::C2), rx: (RxDma3, c3s, dma1::C3)), } #[cfg(any(feature = "stm32l4x5", feature = "stm32l4x6",))] hal! { - UART4: (uart4, APB1R1, uart4en, uart4rst, pclk1, tx: (c3s, dma2::C3), rx: (c5s, dma2::C5)), + UART4: (uart4, APB1R1, uart4en, uart4rst, pclk1, tx: (TxDma4, c3s, dma2::C3), rx: (RxDma4, c5s, dma2::C5)), } #[cfg(any(feature = "stm32l4x5", feature = "stm32l4x6",))] hal! { - UART5: (uart5, APB1R1, uart5en, uart5rst, pclk1, tx: (c1s, dma2::C1), rx: (c2s, dma2::C2)), + UART5: (uart5, APB1R1, uart5en, uart5rst, pclk1, tx: (TxDma5, c1s, dma2::C1), rx: (RxDma5, c2s, dma2::C2)), } impl fmt::Write for Serial diff --git a/src/spi.rs b/src/spi.rs index f00cde83..27f221f1 100644 --- a/src/spi.rs +++ b/src/spi.rs @@ -6,13 +6,17 @@ //! don't have it shouldn't attempt to use it. Relevant info is on user-manual level. use core::ptr; +use core::sync::atomic; +use core::sync::atomic::Ordering; -use crate::hal::spi::{FullDuplex, Mode, Phase, Polarity}; - +use crate::dma::{self, dma1, dma2, TransferPayload}; use crate::gpio::{Alternate, Floating, Input, AF5}; +use crate::hal::spi::{FullDuplex, Mode, Phase, Polarity}; use crate::rcc::{Clocks, APB1R1, APB2}; use crate::time::Hertz; +use embedded_dma::{StaticReadBuffer, StaticWriteBuffer}; + /// SPI error #[non_exhaustive] #[derive(Debug)] @@ -366,3 +370,426 @@ pins!(SPI2, AF5, SCK: [PB13, PB10, PD1], MISO: [PB14, PC2, PD3], MOSI: [PB15, PC3, PD4]); + +pub struct SpiPayload { + spi: Spi, +} + +pub type SpiRxDma = dma::RxDma, CHANNEL>; + +pub type SpiTxDma = dma::TxDma, CHANNEL>; + +pub type SpiRxTxDma = dma::RxTxDma, RXCH, TXCH>; + +macro_rules! spi_dma { + ($SPIX:ident, $RX_CH:path, $RX_CHX:ident, $RX_MAPX:ident, $TX_CH:path, $TX_CHX:ident, $TX_MAPX:ident) => { + impl dma::Receive for SpiRxDma<$SPIX, PINS, $RX_CH> { + type RxChannel = $RX_CH; + type TransmittedWord = u8; + } + + impl dma::Transmit for SpiTxDma<$SPIX, PINS, $TX_CH> { + type TxChannel = $TX_CH; + type ReceivedWord = u8; + } + + impl dma::ReceiveTransmit for SpiRxTxDma<$SPIX, PINS, $RX_CH, $TX_CH> { + type RxChannel = $RX_CH; + type TxChannel = $TX_CH; + type TransferedWord = u8; + } + + impl Spi<$SPIX, PINS> { + pub fn with_rx_dma(self, mut channel: $RX_CH) -> SpiRxDma<$SPIX, PINS, $RX_CH> { + let payload = SpiPayload { spi: self }; + + // Perform one-time setup actions to keep the work minimal when using the driver. + + channel.set_peripheral_address( + unsafe { &(*$SPIX::ptr()).dr as *const _ as u32 }, + false, + ); + channel.cselr().modify(|_, w| w.$RX_CHX().$RX_MAPX()); + channel.ccr().modify(|_, w| { + w + // memory to memory mode disabled + .mem2mem() + .clear_bit() + // medium channel priority level + .pl() + .medium() + // 8-bit memory size + .msize() + .bits8() + // 8-bit peripheral size + .psize() + .bits8() + // circular mode disabled + .circ() + .clear_bit() + // write to memory + .dir() + .clear_bit() + }); + + SpiRxDma { payload, channel } + } + + pub fn with_tx_dma(self, mut channel: $TX_CH) -> SpiTxDma<$SPIX, PINS, $TX_CH> { + let payload = SpiPayload { spi: self }; + + // Perform one-time setup actions to keep the work minimal when using the driver. + + channel.set_peripheral_address( + unsafe { &(*$SPIX::ptr()).dr as *const _ as u32 }, + false, + ); + channel.cselr().modify(|_, w| w.$TX_CHX().$TX_MAPX()); + channel.ccr().modify(|_, w| { + w + // memory to memory mode disabled + .mem2mem() + .clear_bit() + // medium channel priority level + .pl() + .medium() + // 8-bit memory size + .msize() + .bits8() + // 8-bit peripheral size + .psize() + .bits8() + // circular mode disabled + .circ() + .clear_bit() + // write to peripheral + .dir() + .set_bit() + }); + + SpiTxDma { payload, channel } + } + + pub fn with_rxtx_dma( + self, + mut rx_channel: $RX_CH, + mut tx_channel: $TX_CH, + ) -> SpiRxTxDma<$SPIX, PINS, $RX_CH, $TX_CH> { + let payload = SpiPayload { spi: self }; + + // Perform one-time setup actions to keep the work minimal when using the driver. + + // + // Setup RX channel + // + rx_channel.set_peripheral_address( + unsafe { &(*$SPIX::ptr()).dr as *const _ as u32 }, + false, + ); + rx_channel.cselr().modify(|_, w| w.$RX_CHX().$RX_MAPX()); + + rx_channel.ccr().modify(|_, w| { + w + // memory to memory mode disabled + .mem2mem() + .clear_bit() + // medium channel priority level + .pl() + .medium() + // 8-bit memory size + .msize() + .bits8() + // 8-bit peripheral size + .psize() + .bits8() + // circular mode disabled + .circ() + .clear_bit() + // write to memory + .dir() + .clear_bit() + }); + + // + // Setup TX channel + // + tx_channel.set_peripheral_address( + unsafe { &(*$SPIX::ptr()).dr as *const _ as u32 }, + false, + ); + tx_channel.cselr().modify(|_, w| w.$TX_CHX().$TX_MAPX()); + + tx_channel.ccr().modify(|_, w| { + w + // memory to memory mode disabled + .mem2mem() + .clear_bit() + // medium channel priority level + .pl() + .medium() + // 8-bit memory size + .msize() + .bits8() + // 8-bit peripheral size + .psize() + .bits8() + // circular mode disabled + .circ() + .clear_bit() + // write to peripheral + .dir() + .set_bit() + }); + + SpiRxTxDma { + payload, + rx_channel, + tx_channel, + } + } + } + + impl SpiRxDma<$SPIX, PINS, $RX_CH> { + pub fn split(mut self) -> (Spi<$SPIX, PINS>, $RX_CH) { + self.stop(); + (self.payload.spi, self.channel) + } + } + + impl SpiTxDma<$SPIX, PINS, $TX_CH> { + pub fn split(mut self) -> (Spi<$SPIX, PINS>, $TX_CH) { + self.stop(); + (self.payload.spi, self.channel) + } + } + + impl SpiRxTxDma<$SPIX, PINS, $RX_CH, $TX_CH> { + pub fn split(mut self) -> (Spi<$SPIX, PINS>, $RX_CH, $TX_CH) { + self.stop(); + (self.payload.spi, self.rx_channel, self.tx_channel) + } + } + + impl dma::TransferPayload for SpiRxDma<$SPIX, PINS, $RX_CH> { + fn start(&mut self) { + // Setup DMA channels in accordance with RM 40.4.9, subheading "Communication using + // DMA (direct memory addressing)". + // It is mandatory to follow these steps in order: + // + // 0. SPI disabled during setup. + // 1. Enable DMA Rx buffer in the RXDMAEN bit in the SPI_CR2 register, if DMA Rx is used. + // 2. Enable DMA streams for Tx and Rx in DMA registers, if the streams are used. + // 3. Enable DMA Tx buffer in the TXDMAEN bit in the SPI_CR2 register, if DMA Tx is used. + // 4. Enable the SPI by setting the SPE bit. + self.payload.spi.spi.cr1.modify(|_, w| w.spe().clear_bit()); // 0. + self.payload + .spi + .spi + .cr2 + .modify(|_, w| w.rxdmaen().set_bit()); // 1. + self.channel.start(); // 2. + self.payload.spi.spi.cr1.modify(|_, w| w.spe().set_bit()); // 4. + } + + fn stop(&mut self) { + // Stop DMA channels in accordance with RM 40.4.9, subheading "Communication using + // DMA (direct memory addressing)". + // It is mandatory to follow these steps in order: + // + // 1. Disable DMA streams for Tx and Rx in the DMA registers, if the streams are used. + // 2. Disable the SPI by following the SPI disable procedure. + // 3. Disable DMA Tx and Rx buffers by clearing the TXDMAEN and RXDMAEN bits in the + // SPI_CR2 register, if DMA Tx and/or DMA Rx are used. + self.channel.stop(); // 1. + self.payload.spi.spi.cr1.modify(|_, w| w.spe().clear_bit()); // 2. + self.payload + .spi + .spi + .cr2 + .modify(|_, w| w.rxdmaen().clear_bit()); // 3. + } + } + + impl dma::TransferPayload for SpiTxDma<$SPIX, PINS, $TX_CH> { + fn start(&mut self) { + // Setup DMA channels in accordance with RM 40.4.9, subheading "Communication using + // DMA (direct memory addressing)". + // It is mandatory to follow these steps in order: + // + // 0. SPI disabled during setup. + // 1. Enable DMA Rx buffer in the RXDMAEN bit in the SPI_CR2 register, if DMA Rx is used. + // 2. Enable DMA streams for Tx and Rx in DMA registers, if the streams are used. + // 3. Enable DMA Tx buffer in the TXDMAEN bit in the SPI_CR2 register, if DMA Tx is used. + // 4. Enable the SPI by setting the SPE bit. + self.payload.spi.spi.cr1.modify(|_, w| w.spe().clear_bit()); // 0. + self.channel.start(); // 2. + self.payload + .spi + .spi + .cr2 + .modify(|_, w| w.txdmaen().set_bit()); // 3. + self.payload.spi.spi.cr1.modify(|_, w| w.spe().set_bit()); // 4. + } + + fn stop(&mut self) { + // Stop DMA channels in accordance with RM 40.4.9, subheading "Communication using + // DMA (direct memory addressing)". + // It is mandatory to follow these steps in order: + // + // 1. Disable DMA streams for Tx and Rx in the DMA registers, if the streams are used. + // 2. Disable the SPI by following the SPI disable procedure. + // 3. Disable DMA Tx and Rx buffers by clearing the TXDMAEN and RXDMAEN bits in the + // SPI_CR2 register, if DMA Tx and/or DMA Rx are used. + self.channel.stop(); // 1. + self.payload.spi.spi.cr1.modify(|_, w| w.spe().clear_bit()); // 2. + self.payload + .spi + .spi + .cr2 + .modify(|_, w| w.txdmaen().clear_bit()); // 3. + } + } + + impl dma::TransferPayload for SpiRxTxDma<$SPIX, PINS, $RX_CH, $TX_CH> { + fn start(&mut self) { + // Setup DMA channels in accordance with RM 40.4.9, subheading "Communication using + // DMA (direct memory addressing)". + // It is mandatory to follow these steps in order: + // + // 0. SPI disabled during setup. + // 1. Enable DMA Rx buffer in the RXDMAEN bit in the SPI_CR2 register, if DMA Rx is used. + // 2. Enable DMA streams for Tx and Rx in DMA registers, if the streams are used. + // 3. Enable DMA Tx buffer in the TXDMAEN bit in the SPI_CR2 register, if DMA Tx is used. + // 4. Enable the SPI by setting the SPE bit. + self.payload.spi.spi.cr1.modify(|_, w| w.spe().clear_bit()); // 0. + self.payload + .spi + .spi + .cr2 + .modify(|_, w| w.rxdmaen().set_bit()); // 1. + self.rx_channel.start(); // 2. + self.tx_channel.start(); // 2. + self.payload + .spi + .spi + .cr2 + .modify(|_, w| w.txdmaen().set_bit()); // 3. + self.payload.spi.spi.cr1.modify(|_, w| w.spe().set_bit()); // 4. + } + + fn stop(&mut self) { + // Stop DMA channels in accordance with RM 40.4.9, subheading "Communication using + // DMA (direct memory addressing)". + // It is mandatory to follow these steps in order: + // + // 1. Disable DMA streams for Tx and Rx in the DMA registers, if the streams are used. + // 2. Disable the SPI by following the SPI disable procedure. + // 3. Disable DMA Tx and Rx buffers by clearing the TXDMAEN and RXDMAEN bits in the + // SPI_CR2 register, if DMA Tx and/or DMA Rx are used. + self.tx_channel.stop(); // 1. + self.rx_channel.stop(); // 1. + self.payload.spi.spi.cr1.modify(|_, w| w.spe().clear_bit()); // 2. + self.payload + .spi + .spi + .cr2 + .modify(|_, w| w.rxdmaen().clear_bit().txdmaen().clear_bit()); // 3. + } + } + + impl dma::ReadDma for SpiRxDma<$SPIX, PINS, $RX_CH> + where + B: StaticWriteBuffer, + { + fn read(mut self, mut buffer: B) -> dma::Transfer { + // Setup DMA channels in accordance with RM 40.4.9, subheading "Communication using + // DMA (direct memory addressing)" + + // NOTE(unsafe) We own the buffer now and we won't call other `&mut` on it + // until the end of the transfer. + let (ptr, len) = unsafe { buffer.static_write_buffer() }; + + // Setup RX channel addresses and length + self.channel.set_memory_address(ptr as u32, true); + self.channel.set_transfer_length(len as u16); + + // Fences and start + atomic::compiler_fence(Ordering::Release); + self.start(); + + dma::Transfer::w(buffer, self) + } + } + + impl dma::WriteDma for SpiTxDma<$SPIX, PINS, $TX_CH> + where + B: StaticReadBuffer, + { + fn write(mut self, buffer: B) -> dma::Transfer { + // Setup DMA channels in accordance with RM 40.4.9, subheading "Communication using + // DMA (direct memory addressing)" + + // NOTE(unsafe) We own the buffer now and we won't call other `&mut` on it + // until the end of the transfer. + let (ptr, len) = unsafe { buffer.static_read_buffer() }; + + // Setup TX channel addresses and length + self.channel.set_memory_address(ptr as u32, true); + self.channel.set_transfer_length(len as u16); + + // Fences and start + atomic::compiler_fence(Ordering::Release); + self.start(); + + dma::Transfer::r(buffer, self) + } + } + + impl dma::TransferDma for SpiRxTxDma<$SPIX, PINS, $RX_CH, $TX_CH> + where + B: StaticWriteBuffer, + { + fn transfer(mut self, mut buffer: B) -> dma::Transfer { + // Setup DMA channels in accordance with RM 40.4.9, subheading "Communication using + // DMA (direct memory addressing)" + + // Transfer: we use the same buffer for RX and TX + + // NOTE(unsafe) We own the buffer now and we won't call other `&mut` on it + // until the end of the transfer. + let (ptr, len) = unsafe { buffer.static_write_buffer() }; + + // Setup RX channel addresses and length + self.rx_channel.set_memory_address(ptr as u32, true); + self.rx_channel.set_transfer_length(len as u16); + + // Setup TX channel addresses and length + self.tx_channel.set_memory_address(ptr as u32, true); + self.tx_channel.set_transfer_length(len as u16); + + // Fences and start + atomic::compiler_fence(Ordering::Release); + self.start(); + + dma::Transfer::rw(buffer, self) + } + } + }; +} + +spi_dma!(SPI1, dma1::C2, c2s, map1, dma1::C3, c3s, map1); +#[cfg(any( + feature = "stm32l4x1", + feature = "stm32l4x3", + feature = "stm32l4x5", + feature = "stm32l4x6", +))] +spi_dma!(SPI2, dma1::C4, c4s, map1, dma1::C5, c5s, map1); +// spi_dma!(SPI1, dma2::C3, c3s, map4, dma2::C4, c4s, map4); +#[cfg(any( + feature = "stm32l4x1", + feature = "stm32l4x2", + feature = "stm32l4x5", + feature = "stm32l4x6", +))] +spi_dma!(SPI3, dma2::C1, c1s, map3, dma2::C2, c2s, map3);