8 Commits

Author SHA1 Message Date
Priec
1a4c071417 time for big update from now on 2025-10-31 22:37:23 +01:00
Priec
8ce9ee9f6c dma Rx working 2025-10-31 17:28:34 +01:00
Priec
28b468902a Rx is not using dma now 2025-10-31 14:31:25 +01:00
Priec
0ecf821e40 moved properly 2025-10-31 13:19:54 +01:00
Priec
8de34e13d9 solution detached from main for async buffered generalized2 2025-10-31 13:00:21 +01:00
Priec
457d783d3b FINAL FIX WORKING OH MY GOSH YES, We have to leak the timer to keep it toggled on after going out of scope to not call destructor 2025-10-31 11:46:21 +01:00
Priec
172dd899f9 debugging 2025-10-31 10:26:33 +01:00
Priec
f56fe0561b timer is now separated 2025-10-31 00:05:19 +01:00
11 changed files with 336 additions and 101 deletions

View File

@@ -7,61 +7,108 @@ use defmt::*;
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, pipe::Pipe}; use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, pipe::Pipe};
use embassy_time::{Duration, Timer}; use embassy_time::{Duration, Timer};
use dma_gpio::dma_timer::init_tim6_for_uart;
use dma_gpio::dma_timer::init_tim7_for_uart;
use embassy_stm32::gpio::Input;
use embassy_stm32::gpio::Pull;
use dma_gpio::gpio_dma_uart_rx::GpioDmaRx;
use {defmt_rtt as _, panic_probe as _}; use {defmt_rtt as _, panic_probe as _};
use embassy_stm32::{ use embassy_stm32::{
gpio::{Level, Output, Speed}, gpio::{Level, Output, Speed},
peripherals::{GPDMA1_CH0, TIM6}, peripherals::GPDMA1_CH0,
rcc, peripherals::GPDMA1_CH1,
timer::low_level::Timer as LlTimer,
}; };
use embassy_stm32::Peri; use embassy_stm32::Peri;
use dma_gpio::gpio_dma_uart::{ use dma_gpio::gpio_dma_uart_tx::{
write_uart_frames_to_pipe, GpioDmaBsrrTx, Parity, StopBits, UartConfig, TIM6_UP_REQ, write_uart_frames_to_pipe, GpioDmaBsrrTx, Parity, StopBits, UartConfig,
}; };
static PIPE: Pipe<CriticalSectionRawMutex, 256> = Pipe::new(); static PIPE_TX: Pipe<CriticalSectionRawMutex, 256> = Pipe::new();
static PIPE_RX: Pipe<CriticalSectionRawMutex, 256> = Pipe::new();
// Baud rate: one TIM6 update equals one UART bit-time // Baud rate: one TIM6 update equals one UART bit-time
const BAUD: u32 = 115_200; const BAUD: u32 = 115_200;
const TX_PIN_BIT: u8 = 2; // PA2 const TX_PIN_BIT: u8 = 2; // PA2
const TX_OVERSAMPLE: u16 = 1;
const RX_OVERSAMPLE: u16 = 16;
const UART_CFG: UartConfig = UartConfig { const UART_CFG: UartConfig = UartConfig {
data_bits: 8, data_bits: 8,
parity: Parity::None, parity: Parity::None,
stop_bits: StopBits::One, stop_bits: StopBits::One,
}; };
static mut RX_DMA_BUF: [u32; 512] = [0; 512];
fn dump_tim6_regs() {
// PAC path for STM32U5: module `tim6`, type `Tim6` with ptr()
use embassy_stm32::pac::timer::TimBasic;
let tim = unsafe { TimBasic::from_ptr(0x4000_1000usize as _) };
let sr = tim.sr().read();
let dier = tim.dier().read();
let cr1 = tim.cr1().read();
let arr = tim.arr().read().arr();
let psc = tim.psc().read();
info!(
"TIM6: CR1.CEN={} DIER.UDE={} SR.UIF={} PSC={} ARR={}",
cr1.cen(),
dier.ude(),
sr.uif(),
psc,
arr
);
}
fn dump_dma_ch0_regs() {
// PAC path for GPDMA1: module `gpdma1`, type `Gpdma1`
use embassy_stm32::pac::gpdma::Gpdma;
let dma = unsafe { Gpdma::from_ptr(0x4002_0000usize as _) };
let ch = dma.ch(0);
let cr = ch.cr().read();
let tr1 = ch.tr1().read();
let tr2 = ch.tr2().read();
let br1 = ch.br1().read();
info!(
"GPDMA1_CH0: EN={} PRIO={} SDW={} DDW={} SINC={} DINC={} REQSEL={} SWREQ={} DREQ={} BNDT={}",
cr.en(),
cr.prio(),
tr1.sdw(),
tr1.ddw(),
tr1.sinc(),
tr1.dinc(),
tr2.reqsel(),
tr2.swreq(),
tr2.dreq(),
br1.bndt()
);
}
#[embassy_executor::main] #[embassy_executor::main]
async fn main(spawner: Spawner) { async fn main(spawner: Spawner) {
let p = embassy_stm32::init(Default::default()); let p = embassy_stm32::init(Default::default());
info!("DMA Pipe -> GPIO UART-like TX"); info!("Hehe");
// PA3 as Rx "wire"
let pa3_rx = Input::new(p.PA3, Pull::Up);
// PA2 is the TX "wire" // PA2 is the TX "wire"
let _pa2 = Output::new(p.PA2, Level::High, Speed::VeryHigh); let _pa2 = Output::new(p.PA2, Level::High, Speed::VeryHigh);
drop(_pa2); // drop(_pa2);
init_tim6_for_uart(p.TIM6, BAUD, TX_OVERSAMPLE); // TX
// TIM6 generates one DMA request per bit-time init_tim7_for_uart(p.TIM7, BAUD, RX_OVERSAMPLE); // RX
let tim6 = LlTimer::new(p.TIM6); dump_tim6_regs();
let f_tim6 = rcc::frequency::<TIM6>().0;
let arr = (f_tim6 / BAUD).saturating_sub(1) as u16;
tim6.regs_basic().arr().modify(|w| w.set_arr(arr));
tim6.regs_basic().dier().modify(|w| w.set_ude(true));
tim6.regs_basic().cr1().modify(|w| {
w.set_opm(false);
w.set_cen(true);
});
// Start DMA consumer task // Start DMA consumer task
spawner.spawn(dma_tx_task(p.GPDMA1_CH0)).unwrap(); spawner.spawn(tx_dma_task(p.GPDMA1_CH0)).unwrap();
spawner.spawn(rx_dma_task(p.GPDMA1_CH1)).unwrap();
// Example: transmit a string as UART frames via the Pipe // Example: transmit a string as UART frames via the Pipe
loop { loop {
write_uart_frames_to_pipe( write_uart_frames_to_pipe(
&PIPE, &PIPE_TX,
TX_PIN_BIT, TX_PIN_BIT,
b"Hello, DMA UART (configurable)!\r\n", b"Hello marshmallow\r\n",
&UART_CFG, &UART_CFG,
).await; ).await;
Timer::after(Duration::from_secs(2)).await; Timer::after(Duration::from_secs(2)).await;
@@ -69,20 +116,40 @@ async fn main(spawner: Spawner) {
} }
#[embassy_executor::task] #[embassy_executor::task]
async fn dma_tx_task(ch: Peri<'static, GPDMA1_CH0>) { async fn rx_dma_task(ch: Peri<'static, GPDMA1_CH1>) {
let buf_ptr = core::ptr::addr_of_mut!(RX_DMA_BUF);
let buf = unsafe { &mut *buf_ptr };
let mut rx = GpioDmaRx::new(ch, 3 /*PA3 bit*/, buf, &PIPE_RX);
rx.run().await;
}
#[embassy_executor::task]
async fn tx_dma_task(ch: Peri<'static, GPDMA1_CH0>) {
let mut tx = GpioDmaBsrrTx::new(ch); let mut tx = GpioDmaBsrrTx::new(ch);
info!("DMA task started, waiting for frames..."); info!("DMA task started, waiting for frames...");
loop { loop {
// Read one 32-bit BSRR word (4 bytes) from the Pipe // Read one 32-bit BSRR word (4 bytes) from the Pipe
let mut b = [0u8; 4]; let mut b = [0u8; 4];
let n = PIPE.read(&mut b).await; let n = PIPE_TX.read(&mut b).await;
if n != 4 { if n != 4 {
continue; continue;
} }
let w = u32::from_le_bytes(b); let w = u32::from_le_bytes(b);
info!("DMA write 0x{:08X} -> GPIOA.BSRR", w); info!("DMA write 0x{:08X} -> GPIOA.BSRR", w);
tx.write_word(w).await; match embassy_time::with_timeout(
Duration::from_millis(20),
tx.write_word(w),
)
.await
{
Ok(()) => {}
Err(_) => {
warn!("DMA timeout: no TIM6 request");
dump_tim6_regs();
dump_dma_ch0_regs();
}
}
} }
} }

58
dma_gpio/src/dma_timer.rs Normal file
View File

@@ -0,0 +1,58 @@
// src/dma_timer.rs
use embassy_stm32::{
peripherals::{TIM6, TIM7},
rcc,
timer::low_level::Timer,
Peri,
};
use core::mem;
use embassy_stm32::timer::BasicInstance;
use embassy_stm32::pac::timer::vals::Urs;
/// Initializes TIM6 to tick at `baud * oversample` frequency.
/// Each TIM6 update event triggers one DMA beat.
pub fn init_tim6_for_uart<'d>(tim6: Peri<'d, TIM6>, baud: u32, oversample: u16) {
rcc::enable_and_reset::<TIM6>();
let ll = Timer::new(tim6);
configure_basic_timer(&ll, baud, oversample);
mem::forget(ll);
}
/// Initializes TIM7 to tick at `baud * oversample` frequency.
/// Each TIM7 update event triggers one DMA beat.
pub fn init_tim7_for_uart<'d>(tim7: Peri<'d, TIM7>, baud: u32, oversample: u16) {
rcc::enable_and_reset::<TIM7>();
let ll = Timer::new(tim7);
configure_basic_timer(&ll, baud, oversample);
mem::forget(ll);
}
// Shared internal helper — identical CR1/ARR setup
fn configure_basic_timer<T: BasicInstance>(ll: &Timer<'_, T>, baud: u32, oversample: u16) {
let f_timer = rcc::frequency::<T>().0;
let target = baud.saturating_mul(oversample.max(1) as u32).max(1);
// Compute ARR (prescaler = 0)
let mut arr = (f_timer / target).saturating_sub(1) as u16;
if arr == 0 { arr = 1; }
ll.regs_basic().cr1().write(|w| {
w.set_cen(false);
w.set_opm(false);
w.set_udis(false);
w.set_urs(Urs::ANY_EVENT);
});
ll.regs_basic().psc().write_value(0u16);
ll.regs_basic().arr().write(|w| w.set_arr(arr));
ll.regs_basic().dier().modify(|w| w.set_ude(true));
ll.regs_basic().egr().write(|w| w.set_ug(true));
ll.regs_basic().cr1().write(|w| {
w.set_opm(false);
w.set_cen(true);
w.set_udis(false);
w.set_urs(Urs::ANY_EVENT);
});
}

View File

@@ -0,0 +1,57 @@
// src/gpio_dma_uart_rx.rs
use embassy_stm32::{
dma::{Request, Transfer, TransferOptions},
peripherals::GPDMA1_CH1,
Peri,
};
use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, pipe::Pipe};
// RM0456 tabulka 137
pub const TIM7_UP_REQ: Request = 5;
pub struct GpioDmaRx<'d, const N: usize> {
ch: Peri<'d, GPDMA1_CH1>,
pin_bit: u8,
buf: &'d mut [u32; N],
opts: TransferOptions,
pipe_rx: &'d Pipe<CriticalSectionRawMutex, 256>,
}
impl<'d, const N: usize> GpioDmaRx<'d, N> {
pub fn new(
ch: Peri<'d, GPDMA1_CH1>,
pin_bit: u8,
buf: &'d mut [u32; N],
pipe_rx: &'d Pipe<CriticalSectionRawMutex, 256>,
) -> Self {
Self {
ch,
pin_bit,
buf,
opts: TransferOptions::default(),
pipe_rx,
}
}
pub async fn run(&mut self) -> ! {
loop {
let gpioa_idr_addr = embassy_stm32::pac::GPIOA.as_ptr() as *mut u32;
unsafe {
Transfer::new_read(
self.ch.reborrow(),
TIM7_UP_REQ,
gpioa_idr_addr,
&mut self.buf[..],
self.opts,
)
}
.await;
for &word in self.buf.iter() {
let bit_high = ((word >> self.pin_bit) & 1) as u8;
self.pipe_rx.write(&[bit_high]).await;
}
}
}
}

View File

@@ -6,6 +6,7 @@ use embassy_stm32::{
}; };
use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, pipe::Pipe}; use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, pipe::Pipe};
// kapitola 17.4.11 - 2 casovace pre 2 DMA
pub const TIM6_UP_REQ: Request = 4; // Table 137: tim6_upd_dma, strana 687 STM32U5xx datasheet pub const TIM6_UP_REQ: Request = 4; // Table 137: tim6_upd_dma, strana 687 STM32U5xx datasheet
#[derive(Clone, Copy, Debug, PartialEq, Eq)] #[derive(Clone, Copy, Debug, PartialEq, Eq)]

View File

@@ -1,3 +1,9 @@
#![no_std] #![no_std]
pub mod gpio_dma_uart;
pub use gpio_dma_uart::*; pub mod gpio_dma_uart_tx;
pub mod gpio_dma_uart_rx;
pub mod dma_timer;
pub use gpio_dma_uart_tx::*;
pub use gpio_dma_uart_rx::*;
pub use dma_timer::*;

View File

@@ -1,93 +1,51 @@
// src/bin/main.rs // src/bin/main.rs
#![no_std] #![no_std]
#![no_main] #![no_main]
use defmt::*; use defmt::*;
use {defmt_rtt as _, panic_probe as _};
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_stm32::usart::{BufferedInterruptHandler, BufferedUart, Config};
use embassy_stm32::bind_interrupts; use embassy_stm32::bind_interrupts;
use embassy_stm32::peripherals; use embassy_stm32::peripherals;
use embassy_stm32::usart::{BufferedInterruptHandler, BufferedUart, Config}; use embassy_time::Instant;
use embedded_io_async::{Read, Write};
use embassy_time::{Timer, Duration, Instant};
use static_cell::StaticCell; use static_cell::StaticCell;
use embassy_futures::yield_now;
use {defmt_rtt as _, panic_probe as _};
use embassy_futures::select::{select, Either};
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
use embassy_sync::pipe::Pipe;
use async_uart::safety::{preflight_and_suggest_yield_period, RX_PIPE_CAP, TX_PIPE_CAP};
static UART_TX: Pipe<CriticalSectionRawMutex, TX_PIPE_CAP> = Pipe::new(); use async_uart::uart::usart1;
static UART_RX: Pipe<CriticalSectionRawMutex, RX_PIPE_CAP> = Pipe::new();
bind_interrupts!( bind_interrupts!(struct Irqs {
struct Irqs {
USART1 => BufferedInterruptHandler<peripherals::USART1>; USART1 => BufferedInterruptHandler<peripherals::USART1>;
} });
);
#[embassy_executor::task]
async fn uart_task(mut uart: BufferedUart<'static>) {
let mut rx_byte = [0u8; 1];
let mut tx_buf = [0u8; 64];
loop {
// Wait for either RX or TX events.
let rx_fut = uart.read(&mut rx_byte);
let tx_fut = async {
// Until there's outgoing data in TX pipe
let n = UART_TX.read(&mut tx_buf).await;
n
};
match select(rx_fut, tx_fut).await {
// Incoming data from UART hardware
Either::First(res) => {
if let Ok(_) = res {
// Forward to RX pipe
let _ = UART_RX.write(&rx_byte).await;
let _ = UART_TX.try_write(&rx_byte);
}
}
// Outgoing data waiting in TX pipe
Either::Second(n) => {
unwrap!(uart.write(&tx_buf[..n]).await);
}
}
}
}
#[embassy_executor::main] #[embassy_executor::main]
async fn main(spawner: Spawner) { async fn main(spawner: Spawner) {
info!("tititititi"); info!("boot");
let p = embassy_stm32::init(Default::default()); let p = embassy_stm32::init(Default::default());
static TX_BUF: StaticCell<[u8; 256]> = StaticCell::new();
static RX_BUF: StaticCell<[u8; 256]> = StaticCell::new();
let tx_buf = TX_BUF.init([0; 256]);
let rx_buf = RX_BUF.init([0; 256]);
let mut cfg = Config::default(); let mut cfg = Config::default();
cfg.baudrate = 230_400; cfg.baudrate = 230_400;
// Call preflight and get the computed yield period static TX_BUF: StaticCell<[u8; 256]> = StaticCell::new();
let yield_period = preflight_and_suggest_yield_period(cfg.baudrate); static RX_BUF: StaticCell<[u8; 256]> = StaticCell::new();
let usart = BufferedUart::new( let uart =
BufferedUart::new(
p.USART1, p.USART1,
p.PA10, // RX p.PA10,
p.PA9, // TX p.PA9,
tx_buf, TX_BUF.init([0; 256]),
rx_buf, RX_BUF.init([0; 256]),
Irqs, Irqs,
cfg, cfg,
).unwrap(); ).unwrap();
info!("starting uart task"); let handle = usart1::setup_and_spawn(&spawner, uart, cfg.baudrate);
spawner.spawn(uart_task(usart)).unwrap();
let mut counter: u32 = 0;
let mut rx_buf = [0u8; 64]; let mut rx_buf = [0u8; 64];
let mut last_yield = Instant::now(); let mut last_yield = Instant::now();
loop { loop {
counter = counter.wrapping_add(1); if let Ok(n) = handle.rx.try_read(&mut rx_buf) {
// Poll RX pipe for new data (non-blocking)
if let Ok(n) = UART_RX.try_read(&mut rx_buf) {
if n > 0 { if n > 0 {
if let Ok(s) = core::str::from_utf8(&rx_buf[..n]) { if let Ok(s) = core::str::from_utf8(&rx_buf[..n]) {
info!("RX got: {}", s); info!("RX got: {}", s);
@@ -97,13 +55,9 @@ async fn main(spawner: Spawner) {
} }
} }
// Guaranteed to yield before ISR RX buffer can overflow if Instant::now().duration_since(last_yield) >= handle.yield_period {
if Instant::now().duration_since(last_yield) >= yield_period { embassy_futures::yield_now().await;
yield_now().await;
last_yield = Instant::now(); last_yield = Instant::now();
// info!("Yield mf {}", counter);
} }
// Timer::after(Duration::from_micros(1)).await;
// Timer::after(Duration::from_secs(5)).await;
} }
} }

View File

@@ -1,2 +1,2 @@
#![no_std] #![no_std]
pub mod safety; pub mod uart;

View File

@@ -0,0 +1,65 @@
// src/uart/driver.rs
use defmt::unwrap;
use embassy_executor::Spawner;
use embassy_futures::select::{select, Either};
use embassy_stm32::usart::BufferedUart;
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
use embassy_sync::pipe::Pipe;
use embassy_time::Duration;
use embedded_io_async::{Read, Write};
use crate::uart::safety::{RX_PIPE_CAP, TX_PIPE_CAP};
pub struct UartHandle {
pub tx: &'static Pipe<CriticalSectionRawMutex, TX_PIPE_CAP>,
pub rx: &'static Pipe<CriticalSectionRawMutex, RX_PIPE_CAP>,
pub yield_period: Duration,
}
#[embassy_executor::task]
pub async fn uart_task(
mut uart: BufferedUart<'static>,
tx_pipe: &'static Pipe<CriticalSectionRawMutex, TX_PIPE_CAP>,
rx_pipe: &'static Pipe<CriticalSectionRawMutex, RX_PIPE_CAP>,
) {
let mut rx_byte = [0u8; 1];
let mut tx_buf = [0u8; 64];
loop {
let rx_fut = uart.read(&mut rx_byte);
let tx_fut = async {
let n = tx_pipe.read(&mut tx_buf).await;
n
};
match select(rx_fut, tx_fut).await {
// Incoming data from UART hardware
Either::First(res) => {
if let Ok(_) = res {
// Forward to RX pipe and echo to TX pipe (same behavior as before)
let _ = rx_pipe.write(&rx_byte).await;
let _ = tx_pipe.try_write(&rx_byte);
}
}
// Outgoing data waiting in TX pipe
Either::Second(n) => {
unwrap!(uart.write(&tx_buf[..n]).await);
}
}
}
}
pub fn spawn_for(
spawner: &Spawner,
uart: BufferedUart<'static>,
tx_pipe: &'static Pipe<CriticalSectionRawMutex, TX_PIPE_CAP>,
rx_pipe: &'static Pipe<CriticalSectionRawMutex, RX_PIPE_CAP>,
yield_period: Duration,
) -> UartHandle {
spawner.spawn(uart_task(uart, tx_pipe, rx_pipe)).unwrap();
UartHandle {
tx: tx_pipe,
rx: rx_pipe,
yield_period,
}
}

View File

@@ -0,0 +1,4 @@
// src/uart/mod.rs
pub mod driver;
pub mod usart1;
pub mod safety;

View File

@@ -0,0 +1,23 @@
// src/uart/usart1.rs
use defmt::info;
use embassy_executor::Spawner;
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
use embassy_sync::pipe::Pipe;
use embassy_time::Duration;
use crate::uart::safety::{preflight_and_suggest_yield_period, RX_PIPE_CAP, TX_PIPE_CAP};
use crate::uart::driver::{spawn_for, UartHandle};
// Static pipes and buffers
static UART1_TX_PIPE: Pipe<CriticalSectionRawMutex, TX_PIPE_CAP> = Pipe::new();
static UART1_RX_PIPE: Pipe<CriticalSectionRawMutex, RX_PIPE_CAP> = Pipe::new();
pub fn setup_and_spawn(
spawner: &Spawner,
uart: embassy_stm32::usart::BufferedUart<'static>,
baudrate: u32,
) -> UartHandle {
let yield_period: Duration = preflight_and_suggest_yield_period(baudrate);
info!("USART1 initialized");
spawn_for(spawner, uart, &UART1_TX_PIPE, &UART1_RX_PIPE, yield_period)
}