Async UART TX support

This commit is contained in:
2025-02-11 10:18:32 +01:00
parent 4edba63b02
commit 6e0d417a5c
35 changed files with 757 additions and 199 deletions

View File

@ -24,12 +24,29 @@ and this project adheres to [Semantic Versioning](http://semver.org/).
- I2C `TimingCfg` constructor now returns explicit error instead of generic Error.
Removed the timing configuration error type from the generic I2C error enumeration.
- `PinsA` and `PinsB` constructor do not expect an optional `pac::Ioconfig` argument anymore.
- `IrqCfg` renamed to `InterruptConfig`, kept alias for old name.
- All library provided interrupt handlers now start with common prefix `on_interrupt_*`
- `RxWithIrq` renamed to `RxWithInterrupt`
- `Rx::into_rx_with_irq` does not expect any arguments any more.
- `filter_type` renamed to `configure_filter_type`.
- `level_irq` renamed to `configure_level_interrupt`.
- `edge_irq` renamed to `configure_edge_interrupt`.
- `PinsA` and `PinsB` constructor do not expect an optional IOCONFIG argument anymore.
- UART interrupt management is now handled by the main constructor instead of later stages to
statically ensure one interrupt vector for the UART peripheral. `Uart::new` expects an
optional `InterruptConfig` argument.
- `enable_interrupt` and `disable_interrupt` renamed to `enable_nvic_interrupt` and
`disable_nvic_interrupt` to distinguish them from peripheral interrupts more clearly.
- `port_mux` renamed to `port_function_select`
## Added
- Add `downgrade` method for `Pin` and `upgrade` method for `DynPin` as explicit conversion
methods.
- Asynchronous GPIO support.
- Asynchronous UART TX support.
- Add new `get_tim_raw` unsafe method to retrieve TIM peripheral blocks.
- `Uart::with_with_interrupt` and `Uart::new_without_interrupt`
## [v0.8.0] 2024-09-30

View File

@ -19,6 +19,7 @@ embedded-hal = "1"
embedded-hal-async = "1"
embedded-hal-nb = "1"
embedded-io = "0.6"
embedded-io-async = "0.6"
fugit = "0.3"
typenum = "1"
critical-section = "1"

View File

@ -5,11 +5,11 @@
//! on GPIO pins. Please note that this module does not specify/declare the interrupt handlers
//! which must be provided for async support to work. However, it provides one generic
//! [handler][handle_interrupt_for_async_gpio] which should be called in ALL user interrupt handlers
//! for which handle GPIO interrupts.
//! which handle GPIO interrupts.
//!
//! # Example
//!
//! - [Async GPIO example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/async-gpio/examples/embassy/src/bin/async-gpio.rs)
//! - [Async GPIO example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples/embassy/src/bin/async-gpio.rs)
use core::future::Future;
use embassy_sync::waitqueue::AtomicWaker;
@ -18,7 +18,7 @@ use embedded_hal_async::digital::Wait;
use portable_atomic::AtomicBool;
use va108xx::{self as pac, Irqsel, Sysconfig};
use crate::IrqCfg;
use crate::InterruptConfig;
use super::{
pin, DynGroup, DynPin, DynPinId, InputConfig, InterruptEdge, InvalidPinTypeError, Pin, PinId,
@ -44,7 +44,7 @@ fn pin_id_to_offset(dyn_pin_id: DynPinId) -> usize {
/// complete async operations. The user should call this function in ALL interrupt handlers
/// which handle any GPIO interrupts.
#[inline]
pub fn handle_interrupt_for_async_gpio() {
pub fn on_interrupt_for_asynch_gpio() {
let periphs = unsafe { pac::Peripherals::steal() };
handle_interrupt_for_gpio_and_port(
@ -117,7 +117,7 @@ impl InputPinFuture {
.store(false, core::sync::atomic::Ordering::Relaxed);
pin.interrupt_edge(
edge,
IrqCfg::new(irq, true, true),
InterruptConfig::new(irq, true, true),
Some(sys_cfg),
Some(irq_sel),
)
@ -148,9 +148,9 @@ impl InputPinFuture {
) -> Self {
EDGE_DETECTION[pin_id_to_offset(pin.id())]
.store(false, core::sync::atomic::Ordering::Relaxed);
pin.interrupt_edge(
pin.configure_edge_interrupt(
edge,
IrqCfg::new(irq, true, true),
InterruptConfig::new(irq, true, true),
Some(sys_cfg),
Some(irq_sel),
);

View File

@ -61,7 +61,7 @@ use super::{
reg::RegisterInterface,
InputDynPinAsync,
};
use crate::{clock::FilterClkSel, enable_interrupt, pac, FunSel, IrqCfg};
use crate::{clock::FilterClkSel, enable_nvic_interrupt, pac, FunSel, InterruptConfig};
//==================================================================================================
// DynPinMode configurations
@ -351,7 +351,7 @@ impl DynPin {
pub(crate) fn irq_enb(
&mut self,
irq_cfg: crate::IrqCfg,
irq_cfg: crate::InterruptConfig,
syscfg: Option<&mut va108xx::Sysconfig>,
irqsel: Option<&mut va108xx::Irqsel>,
) {
@ -366,18 +366,18 @@ impl DynPin {
DynGroup::A => {
irqsel
.porta0(self.regs.id().num as usize)
.write(|w| unsafe { w.bits(irq_cfg.irq as u32) });
.write(|w| unsafe { w.bits(irq_cfg.id as u32) });
}
DynGroup::B => {
irqsel
.portb0(self.regs.id().num as usize)
.write(|w| unsafe { w.bits(irq_cfg.irq as u32) });
.write(|w| unsafe { w.bits(irq_cfg.id as u32) });
}
}
}
}
if irq_cfg.enable {
unsafe { enable_interrupt(irq_cfg.irq) };
if irq_cfg.enable_in_nvic {
unsafe { enable_nvic_interrupt(irq_cfg.id) };
}
}
@ -435,7 +435,7 @@ impl DynPin {
pub fn interrupt_edge(
&mut self,
edge_type: InterruptEdge,
irq_cfg: IrqCfg,
irq_cfg: InterruptConfig,
syscfg: Option<&mut pac::Sysconfig>,
irqsel: Option<&mut pac::Irqsel>,
) -> Result<(), InvalidPinTypeError> {
@ -453,7 +453,7 @@ impl DynPin {
pub fn interrupt_level(
&mut self,
level_type: InterruptLevel,
irq_cfg: IrqCfg,
irq_cfg: InterruptConfig,
syscfg: Option<&mut pac::Sysconfig>,
irqsel: Option<&mut pac::Irqsel>,
) -> Result<(), InvalidPinTypeError> {

View File

@ -76,7 +76,7 @@ use super::{DynPin, InputPinAsync};
use crate::{
pac::{Irqsel, Porta, Portb, Sysconfig},
typelevel::Sealed,
IrqCfg,
InterruptConfig,
};
use core::convert::Infallible;
use core::marker::PhantomData;
@ -454,7 +454,7 @@ impl<I: PinId, M: PinMode> Pin<I, M> {
fn irq_enb(
&mut self,
irq_cfg: crate::IrqCfg,
irq_cfg: crate::InterruptConfig,
syscfg: Option<&mut va108xx::Sysconfig>,
irqsel: Option<&mut va108xx::Irqsel>,
) {
@ -581,10 +581,10 @@ impl<I: PinId, C: InputConfig> Pin<I, Input<C>> {
InputPinAsync::new(self, irq)
}
pub fn interrupt_edge(
pub fn configure_edge_interrupt(
&mut self,
edge_type: InterruptEdge,
irq_cfg: IrqCfg,
irq_cfg: InterruptConfig,
syscfg: Option<&mut Sysconfig>,
irqsel: Option<&mut Irqsel>,
) {
@ -592,10 +592,10 @@ impl<I: PinId, C: InputConfig> Pin<I, Input<C>> {
self.irq_enb(irq_cfg, syscfg, irqsel);
}
pub fn interrupt_level(
pub fn configure_level_interrupt(
&mut self,
level_type: InterruptLevel,
irq_cfg: IrqCfg,
irq_cfg: InterruptConfig,
syscfg: Option<&mut Sysconfig>,
irqsel: Option<&mut Irqsel>,
) {
@ -631,7 +631,7 @@ impl<I: PinId, C: OutputConfig> Pin<I, Output<C>> {
pub fn interrupt_edge(
&mut self,
edge_type: InterruptEdge,
irq_cfg: IrqCfg,
irq_cfg: InterruptConfig,
syscfg: Option<&mut Sysconfig>,
irqsel: Option<&mut Irqsel>,
) {
@ -642,7 +642,7 @@ impl<I: PinId, C: OutputConfig> Pin<I, Output<C>> {
pub fn interrupt_level(
&mut self,
level_type: InterruptLevel,
irq_cfg: IrqCfg,
irq_cfg: InterruptConfig,
syscfg: Option<&mut Sysconfig>,
irqsel: Option<&mut Irqsel>,
) {
@ -654,7 +654,7 @@ impl<I: PinId, C: OutputConfig> Pin<I, Output<C>> {
impl<I: PinId, C: InputConfig> Pin<I, Input<C>> {
/// See p.37 and p.38 of the programmers guide for more information.
#[inline]
pub fn filter_type(&mut self, filter: FilterType, clksel: FilterClkSel) {
pub fn configure_filter_type(&mut self, filter: FilterType, clksel: FilterClkSel) {
self.inner.regs.filter_type(filter, clksel);
}
}

View File

@ -25,12 +25,14 @@ pub enum FunSel {
}
#[derive(Debug, Copy, Clone, PartialEq, Eq)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
pub enum PortSel {
PortA,
PortB,
}
#[derive(Copy, Clone, PartialEq, Eq)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
pub enum PeripheralSelect {
PortA = 0,
PortB = 1,
@ -47,31 +49,38 @@ pub enum PeripheralSelect {
Gpio = 24,
}
/// Generic IRQ config which can be used to specify whether the HAL driver will
/// Generic interrupt config which can be used to specify whether the HAL driver will
/// use the IRQSEL register to route an interrupt, and whether the IRQ will be unmasked in the
/// Cortex-M0 NVIC. Both are generally necessary for IRQs to work, but the user might perform
/// this steps themselves
#[derive(Debug, PartialEq, Eq, Clone, Copy)]
pub struct IrqCfg {
pub struct InterruptConfig {
/// Interrupt target vector. Should always be set, might be required for disabling IRQs
pub irq: pac::Interrupt,
/// Specfiy whether IRQ should be routed to an IRQ vector using the IRQSEL peripheral
pub id: pac::Interrupt,
/// Specfiy whether IRQ should be routed to an IRQ vector using the IRQSEL peripheral.
pub route: bool,
/// Specify whether the IRQ is unmasked in the Cortex-M NVIC
pub enable: bool,
/// Specify whether the IRQ is unmasked in the Cortex-M NVIC. If an interrupt is used for
/// multiple purposes, the user can enable the interrupts themselves.
pub enable_in_nvic: bool,
}
impl IrqCfg {
pub fn new(irq: pac::Interrupt, route: bool, enable: bool) -> Self {
IrqCfg { irq, route, enable }
impl InterruptConfig {
pub fn new(id: pac::Interrupt, route: bool, enable_in_nvic: bool) -> Self {
InterruptConfig {
id,
route,
enable_in_nvic,
}
}
}
pub type IrqCfg = InterruptConfig;
#[derive(Debug, PartialEq, Eq)]
pub struct InvalidPin(pub(crate) ());
/// Can be used to manually manipulate the function select of port pins
pub fn port_mux(
pub fn port_function_select(
ioconfig: &mut pac::Ioconfig,
port: PortSel,
pin: u8,
@ -105,7 +114,7 @@ pub fn port_mux(
///
/// This function is `unsafe` because it can break mask-based critical sections.
#[inline]
pub unsafe fn enable_interrupt(irq: pac::Interrupt) {
pub unsafe fn enable_nvic_interrupt(irq: pac::Interrupt) {
unsafe {
cortex_m::peripheral::NVIC::unmask(irq);
}
@ -113,6 +122,6 @@ pub unsafe fn enable_interrupt(irq: pac::Interrupt) {
/// Disable a specific interrupt using the NVIC peripheral.
#[inline]
pub fn disable_interrupt(irq: pac::Interrupt) {
pub fn disable_nvic_interrupt(irq: pac::Interrupt) {
cortex_m::peripheral::NVIC::mask(irq);
}

View File

@ -80,7 +80,7 @@ where
pin
}
pub fn reduce(self) -> ReducedPwmPin<Mode> {
pub fn downgrade(self) -> ReducedPwmPin<Mode> {
self.inner
}
@ -277,6 +277,24 @@ impl<Mode> ReducedPwmPin<Mode> {
}
}
impl<Pin: TimPin, Tim: ValidTim> From<PwmPin<Pin, Tim, PwmA>> for ReducedPwmPin<PwmA>
where
(Pin, Tim): ValidTimAndPin<Pin, Tim>,
{
fn from(value: PwmPin<Pin, Tim, PwmA>) -> Self {
value.downgrade()
}
}
impl<Pin: TimPin, Tim: ValidTim> From<PwmPin<Pin, Tim, PwmB>> for ReducedPwmPin<PwmB>
where
(Pin, Tim): ValidTimAndPin<Pin, Tim>,
{
fn from(value: PwmPin<Pin, Tim, PwmB>) -> Self {
value.downgrade()
}
}
impl From<ReducedPwmPin<PwmA>> for ReducedPwmPin<PwmB> {
fn from(other: ReducedPwmPin<PwmA>) -> Self {
let mut pwmb = Self {

View File

@ -4,10 +4,10 @@
//!
//! - [MS and second tick implementation](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples/simple/examples/timer-ticks.rs)
//! - [Cascade feature example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples/simple/examples/cascade.rs)
pub use crate::IrqCfg;
pub use crate::InterruptConfig;
use crate::{
clock::{enable_peripheral_clock, PeripheralClocks},
enable_interrupt,
enable_nvic_interrupt,
gpio::{
AltFunc1, AltFunc2, AltFunc3, DynPinId, Pin, PinId, PA0, PA1, PA10, PA11, PA12, PA13, PA14,
PA15, PA2, PA24, PA25, PA26, PA27, PA28, PA29, PA3, PA30, PA31, PA4, PA5, PA6, PA7, PA8,
@ -362,7 +362,7 @@ unsafe impl TimRegInterface for TimDynRegister {
pub struct CountdownTimer<Tim: ValidTim> {
tim: Tim,
curr_freq: Hertz,
irq_cfg: Option<IrqCfg>,
irq_cfg: Option<InterruptConfig>,
sys_clk: Hertz,
rst_val: u32,
last_cnt: u32,
@ -415,13 +415,13 @@ impl<Tim: ValidTim> CountdownTimer<Tim> {
pub fn listen(
&mut self,
event: Event,
irq_cfg: IrqCfg,
irq_cfg: InterruptConfig,
irq_sel: Option<&mut pac::Irqsel>,
sys_cfg: Option<&mut pac::Sysconfig>,
) {
match event {
Event::TimeOut => {
cortex_m::peripheral::NVIC::mask(irq_cfg.irq);
cortex_m::peripheral::NVIC::mask(irq_cfg.id);
self.irq_cfg = Some(irq_cfg);
if irq_cfg.route {
if let Some(sys_cfg) = sys_cfg {
@ -430,7 +430,7 @@ impl<Tim: ValidTim> CountdownTimer<Tim> {
if let Some(irq_sel) = irq_sel {
irq_sel
.tim0(Tim::TIM_ID as usize)
.write(|w| unsafe { w.bits(irq_cfg.irq as u32) });
.write(|w| unsafe { w.bits(irq_cfg.id as u32) });
}
}
self.listening = true;
@ -520,8 +520,8 @@ impl<Tim: ValidTim> CountdownTimer<Tim> {
pub fn enable(&mut self) {
if let Some(irq_cfg) = self.irq_cfg {
self.enable_interrupt();
if irq_cfg.enable {
unsafe { enable_interrupt(irq_cfg.irq) };
if irq_cfg.enable_in_nvic {
unsafe { enable_nvic_interrupt(irq_cfg.id) };
}
}
self.tim
@ -719,7 +719,7 @@ impl<TIM: ValidTim> embedded_hal::delay::DelayNs for CountdownTimer<TIM> {
// Set up a millisecond timer on TIM0. Please note that the user still has to provide an IRQ handler
// which should call [default_ms_irq_handler].
pub fn set_up_ms_tick<TIM: ValidTim>(
irq_cfg: IrqCfg,
irq_cfg: InterruptConfig,
sys_cfg: &mut pac::Sysconfig,
irq_sel: Option<&mut pac::Irqsel>,
sys_clk: impl Into<Hertz>,

View File

@ -0,0 +1,264 @@
//! # Async GPIO functionality for the VA108xx family.
//!
//! This module provides the [TxAsync] struct which implements the [embedded_io_async::Write] trait.
//! This trait allows for asynchronous sending of data streams. Please note that this module does
//! not specify/declare the interrupt handlers which must be provided for async support to work.
//! However, it provides two interrupt handlers:
//!
//! - [on_interrupt_uart_a_tx]
//! - [on_interrupt_uart_b_tx]
//!
//! Those should be called in ALL user interrupt handlers which handle UART TX interrupts,
//! depending on which UARTs are used.
//!
//! # Example
//!
//! - [Async UART example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/async-gpio/examples/embassy/src/bin/async-uart.rs)
use core::{cell::RefCell, future::Future};
use critical_section::Mutex;
use embassy_sync::waitqueue::AtomicWaker;
use embedded_io_async::Write;
use portable_atomic::AtomicBool;
use super::*;
static UART_WAKERS: [AtomicWaker; 2] = [const { AtomicWaker::new() }; 2];
static TX_CONTEXTS: [Mutex<RefCell<TxContext>>; 2] =
[const { Mutex::new(RefCell::new(TxContext::new())) }; 2];
// Completion flag. Kept outside of the context structure as an atomic to avoid
// critical section.
static TX_DONE: [AtomicBool; 2] = [const { AtomicBool::new(false) }; 2];
/// This is a generic interrupt handler to handle asynchronous UART TX operations. The user
/// has to call this once in the interrupt handler responsible for UART A TX interrupts for
/// asynchronous operations to work.
pub fn on_interrupt_uart_a_tx() {
on_interrupt_uart_tx(unsafe { pac::Uarta::steal() });
}
/// This is a generic interrupt handler to handle asynchronous UART TX operations. The user
/// has to call this once in the interrupt handler responsible for UART B TX interrupts for
/// asynchronous operations to work.
pub fn on_interrupt_uart_b_tx() {
on_interrupt_uart_tx(unsafe { pac::Uartb::steal() });
}
fn on_interrupt_uart_tx<Uart: Instance>(uart: Uart) {
let irq_enb = uart.irq_enb().read();
// IRQ is not related to TX.
if irq_enb.irq_tx().bit_is_clear() || irq_enb.irq_tx_empty().bit_is_clear() {
return;
}
let tx_status = uart.txstatus().read();
let unexpected_overrun = tx_status.wrlost().bit_is_set();
let mut context = critical_section::with(|cs| {
let context_ref = TX_CONTEXTS[Uart::IDX as usize].borrow(cs);
*context_ref.borrow()
});
context.tx_overrun = unexpected_overrun;
if context.progress >= context.slice.len && !tx_status.wrbusy().bit_is_set() {
uart.irq_enb().modify(|_, w| {
w.irq_tx().clear_bit();
w.irq_tx_empty().clear_bit();
w.irq_tx_status().clear_bit()
});
uart.enable().modify(|_, w| w.txenable().clear_bit());
// Write back updated context structure.
critical_section::with(|cs| {
let context_ref = TX_CONTEXTS[Uart::IDX as usize].borrow(cs);
*context_ref.borrow_mut() = context;
});
// Transfer is done.
TX_DONE[Uart::IDX as usize].store(true, core::sync::atomic::Ordering::Relaxed);
UART_WAKERS[Uart::IDX as usize].wake();
return;
}
// Safety: We documented that the user provided slice must outlive the future, so we convert
// the raw pointer back to the slice here.
let slice = unsafe { core::slice::from_raw_parts(context.slice.data, context.slice.len) };
while context.progress < context.slice.len {
let wrrdy = uart.txstatus().read().wrrdy().bit_is_set();
if !wrrdy {
break;
}
// Safety: TX structure is owned by the future which does not write into the the data
// register, so we can assume we are the only one writing to the data register.
uart.data()
.write(|w| unsafe { w.bits(slice[context.progress] as u32) });
context.progress += 1;
}
// Write back updated context structure.
critical_section::with(|cs| {
let context_ref = TX_CONTEXTS[Uart::IDX as usize].borrow(cs);
*context_ref.borrow_mut() = context;
});
}
#[derive(Debug, Copy, Clone)]
pub struct TxContext {
progress: usize,
tx_overrun: bool,
slice: RawBufSlice,
}
#[allow(clippy::new_without_default)]
impl TxContext {
pub const fn new() -> Self {
Self {
progress: 0,
tx_overrun: false,
slice: RawBufSlice::new_empty(),
}
}
}
#[derive(Debug, Copy, Clone)]
struct RawBufSlice {
data: *const u8,
len: usize,
}
/// Safety: This type MUST be used with mutex to ensure concurrent access is valid.
unsafe impl Send for RawBufSlice {}
impl RawBufSlice {
/// # Safety
///
/// This function stores the raw pointer of the passed data slice. The user MUST ensure
/// that the slice outlives the data structure.
#[allow(dead_code)]
const unsafe fn new(data: &[u8]) -> Self {
Self {
data: data.as_ptr(),
len: data.len(),
}
}
const fn new_empty() -> Self {
Self {
data: core::ptr::null(),
len: 0,
}
}
/// # Safety
///
/// This function stores the raw pointer of the passed data slice. The user MUST ensure
/// that the slice outlives the data structure.
pub unsafe fn set(&mut self, data: &[u8]) {
self.data = data.as_ptr();
self.len = data.len();
}
}
pub struct TxFuture {
uart_idx: usize,
}
impl TxFuture {
/// # Safety
///
/// This function stores the raw pointer of the passed data slice. The user MUST ensure
/// that the slice outlives the data structure.
pub unsafe fn new<Uart: Instance>(tx: &mut Tx<Uart>, data: &[u8]) -> Self {
TX_DONE[Uart::IDX as usize].store(false, core::sync::atomic::Ordering::Relaxed);
tx.disable_interrupts();
tx.disable();
tx.clear_fifo();
let uart_tx = unsafe { tx.uart() };
let init_fill_count = core::cmp::min(data.len(), 16);
// We fill the FIFO.
for data in data.iter().take(init_fill_count) {
uart_tx.data().write(|w| unsafe { w.bits(*data as u32) });
}
critical_section::with(|cs| {
let context_ref = TX_CONTEXTS[Uart::IDX as usize].borrow(cs);
let mut context = context_ref.borrow_mut();
context.slice.set(data);
context.progress = init_fill_count;
// Ensure those are enabled inside a critical section at the same time. Can lead to
// weird glitches otherwise.
tx.enable_interrupts();
tx.enable();
});
Self {
uart_idx: Uart::IDX as usize,
}
}
}
impl Future for TxFuture {
type Output = Result<usize, TxOverrunError>;
fn poll(
self: core::pin::Pin<&mut Self>,
cx: &mut core::task::Context<'_>,
) -> core::task::Poll<Self::Output> {
UART_WAKERS[self.uart_idx].register(cx.waker());
if TX_DONE[self.uart_idx].swap(false, core::sync::atomic::Ordering::Relaxed) {
let progress = critical_section::with(|cs| {
TX_CONTEXTS[self.uart_idx].borrow(cs).borrow().progress
});
return core::task::Poll::Ready(Ok(progress));
}
core::task::Poll::Pending
}
}
impl Drop for TxFuture {
fn drop(&mut self) {
let reg_block = match self.uart_idx {
0 => unsafe { pac::Uarta::reg_block() },
1 => unsafe { pac::Uartb::reg_block() },
_ => unreachable!(),
};
disable_tx_interrupts(reg_block);
disable_tx(reg_block);
}
}
pub struct TxAsync<Uart: Instance> {
tx: Tx<Uart>,
}
impl<Uart: Instance> TxAsync<Uart> {
pub fn new(tx: Tx<Uart>) -> Self {
Self { tx }
}
pub fn release(self) -> Tx<Uart> {
self.tx
}
}
#[derive(Debug, thiserror::Error)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
#[error("TX overrun error")]
pub struct TxOverrunError;
impl embedded_io_async::Error for TxOverrunError {
fn kind(&self) -> embedded_io_async::ErrorKind {
embedded_io_async::ErrorKind::Other
}
}
impl<Uart: Instance> embedded_io::ErrorType for TxAsync<Uart> {
type Error = TxOverrunError;
}
impl<Uart: Instance> Write for TxAsync<Uart> {
/// Write a buffer asynchronously.
///
/// This implementation is not side effect free, and a started future might have already
/// written part of the passed buffer.
async fn write(&mut self, buf: &[u8]) -> Result<usize, Self::Error> {
let fut = unsafe { TxFuture::new(&mut self.tx, buf) };
fut.await
}
}

View File

@ -9,10 +9,10 @@ use core::{convert::Infallible, ops::Deref};
use fugit::RateExtU32;
use va108xx::Uarta;
pub use crate::IrqCfg;
pub use crate::InterruptConfig;
use crate::{
clock::enable_peripheral_clock,
enable_interrupt,
enable_nvic_interrupt,
gpio::pin::{
AltFunc1, AltFunc2, AltFunc3, Pin, PA16, PA17, PA18, PA19, PA2, PA26, PA27, PA3, PA30,
PA31, PA8, PA9, PB18, PB19, PB20, PB21, PB22, PB23, PB6, PB7, PB8, PB9,
@ -48,6 +48,11 @@ impl Pins<pac::Uartb> for (Pin<PB21, AltFunc1>, Pin<PB20, AltFunc1>) {}
// Regular Definitions
//==================================================================================================
#[derive(Debug, PartialEq, Eq, thiserror::Error)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
#[error("no interrupt ID was set")]
pub struct NoInterruptIdWasSet;
#[derive(Debug, PartialEq, Eq, thiserror::Error)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
#[error("transer is pending")]
@ -373,6 +378,16 @@ pub trait Instance: Deref<Target = uart_base::RegisterBlock> {
/// This circumvents the safety guarantees of the HAL.
unsafe fn steal() -> Self;
fn ptr() -> *const uart_base::RegisterBlock;
/// Retrieve the type erased peripheral register block.
///
/// # Safety
///
/// This circumvents the safety guarantees of the HAL.
#[inline(always)]
unsafe fn reg_block() -> &'static uart_base::RegisterBlock {
unsafe { &(*Self::ptr()) }
}
}
impl Instance for pac::Uarta {
@ -380,9 +395,11 @@ impl Instance for pac::Uarta {
const PERIPH_SEL: PeripheralSelect = PeripheralSelect::Uart0;
#[inline(always)]
unsafe fn steal() -> Self {
pac::Peripherals::steal().uarta
}
#[inline(always)]
fn ptr() -> *const uart_base::RegisterBlock {
Uarta::ptr() as *const _
}
@ -393,9 +410,11 @@ impl Instance for pac::Uartb {
const PERIPH_SEL: PeripheralSelect = PeripheralSelect::Uart1;
#[inline(always)]
unsafe fn steal() -> Self {
pac::Peripherals::steal().uartb
}
#[inline(always)]
fn ptr() -> *const uart_base::RegisterBlock {
Uarta::ptr() as *const _
}
@ -592,15 +611,51 @@ where
UartInstance: Instance,
PinsInstance: Pins<UartInstance>,
{
pub fn new(
/// Calls [Self::new] with the interrupt configuration to some valid value.
pub fn new_with_interrupt(
syscfg: &mut va108xx::Sysconfig,
sys_clk: impl Into<Hertz>,
uart: UartInstance,
pins: PinsInstance,
config: impl Into<Config>,
irq_cfg: InterruptConfig,
) -> Self {
Self::new(syscfg, sys_clk, uart, pins, config, Some(irq_cfg))
}
/// Calls [Self::new] with the interrupt configuration to [None].
pub fn new_without_interrupt(
syscfg: &mut va108xx::Sysconfig,
sys_clk: impl Into<Hertz>,
uart: UartInstance,
pins: PinsInstance,
config: impl Into<Config>,
) -> Self {
Self::new(syscfg, sys_clk, uart, pins, config, None)
}
/// Create a new UART peripheral with an interrupt configuration.
///
/// # Arguments
///
/// - `syscfg`: The system configuration register block
/// - `sys_clk`: The system clock frequency
/// - `uart`: The concrete UART peripheral instance.
/// - `pins`: UART TX and RX pin tuple.
/// - `config`: UART specific configuration parameters like baudrate.
/// - `irq_cfg`: Optional interrupt configuration. This should be a valid value if the plan
/// is to use TX or RX functionality relying on interrupts. If only the blocking API without
/// any interrupt support is used, this can be [None].
pub fn new(
syscfg: &mut va108xx::Sysconfig,
sys_clk: impl Into<Hertz>,
uart: UartInstance,
pins: PinsInstance,
config: impl Into<Config>,
opt_irq_cfg: Option<InterruptConfig>,
) -> Self {
crate::clock::enable_peripheral_clock(syscfg, UartInstance::PERIPH_SEL);
Uart {
let uart = Uart {
inner: UartBase {
uart,
tx: Tx::new(unsafe { UartInstance::steal() }),
@ -608,7 +663,21 @@ where
},
pins,
}
.init(config.into(), sys_clk.into())
.init(config.into(), sys_clk.into());
if let Some(irq_cfg) = opt_irq_cfg {
if irq_cfg.route {
enable_peripheral_clock(syscfg, PeripheralSelect::Irqsel);
unsafe { pac::Irqsel::steal() }
.uart0(UartInstance::IDX as usize)
.write(|w| unsafe { w.bits(irq_cfg.id as u32) });
}
if irq_cfg.enable_in_nvic {
// Safety: User has specifically configured this.
unsafe { enable_nvic_interrupt(irq_cfg.id) };
}
}
uart
}
/// This function assumes that the peripheral clock was alredy enabled
@ -686,11 +755,13 @@ where
/// Serial receiver.
///
/// Can be created by using the [Uart::split] or [UartBase::split] API.
pub struct Rx<Uart>(Uart);
pub struct Rx<Uart> {
uart: Uart,
}
impl<Uart: Instance> Rx<Uart> {
fn new(uart: Uart) -> Self {
Self(uart)
Self { uart }
}
/// Direct access to the peripheral structure.
@ -699,22 +770,22 @@ impl<Uart: Instance> Rx<Uart> {
///
/// You must ensure that only registers related to the operation of the RX side are used.
pub unsafe fn uart(&self) -> &Uart {
&self.0
&self.uart
}
#[inline]
pub fn clear_fifo(&self) {
self.0.fifo_clr().write(|w| w.rxfifo().set_bit());
self.uart.fifo_clr().write(|w| w.rxfifo().set_bit());
}
#[inline]
pub fn enable(&mut self) {
self.0.enable().modify(|_, w| w.rxenable().set_bit());
self.uart.enable().modify(|_, w| w.rxenable().set_bit());
}
#[inline]
pub fn disable(&mut self) {
self.0.enable().modify(|_, w| w.rxenable().clear_bit());
self.uart.enable().modify(|_, w| w.rxenable().clear_bit());
}
/// Low level function to read a word from the UART FIFO.
@ -725,7 +796,7 @@ impl<Uart: Instance> Rx<Uart> {
/// value if you use the manual parity mode. See chapter 4.6.2 for more information.
#[inline(always)]
pub fn read_fifo(&self) -> nb::Result<u32, Infallible> {
if self.0.rxstatus().read().rdavl().bit_is_clear() {
if self.uart.rxstatus().read().rdavl().bit_is_clear() {
return Err(nb::Error::WouldBlock);
}
Ok(self.read_fifo_unchecked())
@ -741,20 +812,15 @@ impl<Uart: Instance> Rx<Uart> {
/// value if you use the manual parity mode. See chapter 4.6.2 for more information.
#[inline(always)]
pub fn read_fifo_unchecked(&self) -> u32 {
self.0.data().read().bits()
self.uart.data().read().bits()
}
pub fn into_rx_with_irq(
self,
sysconfig: &mut pac::Sysconfig,
irqsel: &mut pac::Irqsel,
interrupt: pac::Interrupt,
) -> RxWithIrq<Uart> {
RxWithIrq::new(self, sysconfig, irqsel, interrupt)
pub fn into_rx_with_irq(self) -> RxWithInterrupt<Uart> {
RxWithInterrupt::new(self)
}
pub fn release(self) -> Uart {
self.0
self.uart
}
}
@ -811,14 +877,51 @@ impl<Uart: Instance> embedded_io::Read for Rx<Uart> {
}
}
pub fn enable_tx(uart: &uart_base::RegisterBlock) {
uart.enable().modify(|_, w| w.txenable().set_bit());
}
pub fn disable_tx(uart: &uart_base::RegisterBlock) {
uart.enable().modify(|_, w| w.txenable().clear_bit());
}
pub fn enable_tx_interrupts(uart: &uart_base::RegisterBlock) {
uart.irq_enb().modify(|_, w| {
w.irq_tx().set_bit();
w.irq_tx_status().set_bit();
w.irq_tx_empty().set_bit()
});
}
pub fn disable_tx_interrupts(uart: &uart_base::RegisterBlock) {
uart.irq_enb().modify(|_, w| {
w.irq_tx().clear_bit();
w.irq_tx_status().clear_bit();
w.irq_tx_empty().clear_bit()
});
}
/// Serial transmitter
///
/// Can be created by using the [Uart::split] or [UartBase::split] API.
pub struct Tx<Uart>(Uart);
pub struct Tx<Uart> {
uart: Uart,
}
impl<Uart: Instance> Tx<Uart> {
/// Retrieve a TX pin without expecting an explicit UART structure
///
/// # Safety
///
/// Circumvents the HAL safety guarantees.
pub unsafe fn steal() -> Self {
Self {
uart: Uart::steal(),
}
}
fn new(uart: Uart) -> Self {
Self(uart)
Self { uart }
}
/// Direct access to the peripheral structure.
@ -827,22 +930,45 @@ impl<Uart: Instance> Tx<Uart> {
///
/// You must ensure that only registers related to the operation of the TX side are used.
pub unsafe fn uart(&self) -> &Uart {
&self.0
&self.uart
}
#[inline]
pub fn clear_fifo(&self) {
self.0.fifo_clr().write(|w| w.txfifo().set_bit());
self.uart.fifo_clr().write(|w| w.txfifo().set_bit());
}
#[inline]
pub fn enable(&mut self) {
self.0.enable().modify(|_, w| w.txenable().set_bit());
// Safety: We own the UART structure
enable_tx(unsafe { Uart::reg_block() });
}
#[inline]
pub fn disable(&mut self) {
self.0.enable().modify(|_, w| w.txenable().clear_bit());
// Safety: We own the UART structure
disable_tx(unsafe { Uart::reg_block() });
}
/// Enables the IRQ_TX, IRQ_TX_STATUS and IRQ_TX_EMPTY interrupts.
///
/// - The IRQ_TX interrupt is generated when the TX FIFO is at least half empty.
/// - The IRQ_TX_STATUS interrupt is generated when write data is lost due to a FIFO overflow
/// - The IRQ_TX_EMPTY interrupt is generated when the TX FIFO is empty and the TXBUSY signal
/// is 0
#[inline]
pub fn enable_interrupts(&self) {
// Safety: We own the UART structure
enable_tx_interrupts(unsafe { Uart::reg_block() });
}
/// Disables the IRQ_TX, IRQ_TX_STATUS and IRQ_TX_EMPTY interrupts.
///
/// [Self::enable_interrupts] documents the interrupts.
#[inline]
pub fn disable_interrupts(&self) {
// Safety: We own the UART structure
disable_tx_interrupts(unsafe { Uart::reg_block() });
}
/// Low level function to write a word to the UART FIFO.
@ -853,7 +979,7 @@ impl<Uart: Instance> Tx<Uart> {
/// value if you use the manual parity mode. See chapter 11.4.1 for more information.
#[inline(always)]
pub fn write_fifo(&self, data: u32) -> nb::Result<(), Infallible> {
if self.0.txstatus().read().wrrdy().bit_is_clear() {
if self.uart.txstatus().read().wrrdy().bit_is_clear() {
return Err(nb::Error::WouldBlock);
}
self.write_fifo_unchecked(data);
@ -868,7 +994,11 @@ impl<Uart: Instance> Tx<Uart> {
/// API.
#[inline(always)]
pub fn write_fifo_unchecked(&self, data: u32) {
self.0.data().write(|w| unsafe { w.bits(data) });
self.uart.data().write(|w| unsafe { w.bits(data) });
}
pub fn into_async(self) -> TxAsync<Uart> {
TxAsync::new(self)
}
}
@ -931,36 +1061,23 @@ impl<Uart: Instance> embedded_io::Write for Tx<Uart> {
/// then call the [Self::irq_handler_max_size_or_timeout_based] in the interrupt service
/// routine. You have to call [Self::read_fixed_len_or_timeout_based_using_irq] in the ISR to
/// start reading the next packet.
pub struct RxWithIrq<Uart> {
pub rx: Rx<Uart>,
pub interrupt: pac::Interrupt,
}
pub struct RxWithInterrupt<Uart>(Rx<Uart>);
impl<Uart: Instance> RxWithIrq<Uart> {
pub fn new(
rx: Rx<Uart>,
syscfg: &mut pac::Sysconfig,
irqsel: &mut pac::Irqsel,
interrupt: pac::Interrupt,
) -> Self {
enable_peripheral_clock(syscfg, PeripheralSelect::Irqsel);
irqsel
.uart0(Uart::IDX as usize)
.write(|w| unsafe { w.bits(interrupt as u32) });
Self { rx, interrupt }
impl<Uart: Instance> RxWithInterrupt<Uart> {
pub fn new(rx: Rx<Uart>) -> Self {
Self(rx)
}
/// This function should be called once at initialization time if the regular
/// [Self::irq_handler] is used to read the UART receiver to enable and start the receiver.
pub fn start(&mut self) {
self.rx.enable();
self.0.enable();
self.enable_rx_irq_sources(true);
unsafe { enable_interrupt(self.interrupt) };
}
#[inline(always)]
pub fn uart(&self) -> &Uart {
&self.rx.0
&self.0.uart
}
/// This function is used together with the [Self::irq_handler_max_size_or_timeout_based]
@ -1006,7 +1123,7 @@ impl<Uart: Instance> RxWithIrq<Uart> {
pub fn cancel_transfer(&mut self) {
self.disable_rx_irq_sources();
self.rx.clear_fifo();
self.0.clear_fifo();
}
/// This function should be called in the user provided UART interrupt handler.
@ -1017,7 +1134,7 @@ impl<Uart: Instance> RxWithIrq<Uart> {
/// This function will not disable the RX interrupts, so you don't need to call any other
/// API after calling this function to continue emptying the FIFO. RX errors are handled
/// as partial errors and are returned as part of the [IrqResult].
pub fn irq_handler(&mut self, buf: &mut [u8; 16]) -> IrqResult {
pub fn on_interrupt(&mut self, buf: &mut [u8; 16]) -> IrqResult {
let mut result = IrqResult::default();
let irq_end = self.uart().irq_end().read();
@ -1040,7 +1157,7 @@ impl<Uart: Instance> RxWithIrq<Uart> {
if irq_end.irq_rx_to().bit_is_set() {
loop {
// While there is data in the FIFO, write it into the reception buffer
let read_result = self.rx.read();
let read_result = self.0.read();
if let Some(byte) = self.read_handler(&mut result.errors, &read_result) {
buf[result.bytes_read] = byte;
result.bytes_read += 1;
@ -1074,7 +1191,7 @@ impl<Uart: Instance> RxWithIrq<Uart> {
/// If passed buffer is equal to or larger than the specified maximum length, an
/// [BufferTooShortError] will be returned. Other RX errors are treated as partial errors
/// and returned inside the [IrqResultMaxSizeOrTimeout] structure.
pub fn irq_handler_max_size_or_timeout_based(
pub fn on_interrupt_max_size_or_timeout_based(
&mut self,
context: &mut IrqContextTimeoutOrMaxSize,
buf: &mut [u8],
@ -1123,7 +1240,7 @@ impl<Uart: Instance> RxWithIrq<Uart> {
if context.rx_idx == context.max_len {
break;
}
let read_result = self.rx.read();
let read_result = self.0.read();
if let Some(byte) = self.read_handler(&mut result.errors, &read_result) {
buf[context.rx_idx] = byte;
context.rx_idx += 1;
@ -1197,7 +1314,7 @@ impl<Uart: Instance> RxWithIrq<Uart> {
context: &mut IrqContextTimeoutOrMaxSize,
) {
self.disable_rx_irq_sources();
self.rx.disable();
self.0.disable();
res.bytes_read = context.rx_idx;
res.complete = true;
context.mode = IrqReceptionMode::Idle;
@ -1210,6 +1327,9 @@ impl<Uart: Instance> RxWithIrq<Uart> {
/// The user must ensure that these instances are not used to create multiple overlapping
/// UART drivers.
pub unsafe fn release(self) -> Uart {
self.rx.release()
self.0.release()
}
}
pub mod asynch;
pub use asynch::*;