diff --git a/CHANGELOG.md b/CHANGELOG.md index c6b5dd57..00b9a345 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -38,6 +38,7 @@ and this project adheres to [Semantic Versioning](http://semver.org/). ### Added +- `Serial` support for UART4/5 - Allow to set HSE bypass bit in `RCC` clock configuration register to use an external clock input on the `OSC_IN` pin [#485] - initial support of `embedded-hal-1.0` [#416] - Add tools/check.py python script for local check [#467] diff --git a/Cargo.toml b/Cargo.toml index f858b84e..a4305743 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -36,7 +36,7 @@ vcell = "0.1.3" [dependencies.stm32f1] package = "stm32f1-staging" -version = "0.17.1" +version = "0.19.0" features = ["atomics"] [dependencies.embedded-hal-02] diff --git a/examples/can-echo.rs b/examples/can-echo.rs index e399e255..b4c187c0 100644 --- a/examples/can-echo.rs +++ b/examples/can-echo.rs @@ -29,11 +29,10 @@ fn main() -> ! { let rx = gpioa.pa11; let tx = gpioa.pa12; - let can = dp.CAN1.can( - #[cfg(not(feature = "connectivity"))] - dp.USB, - (tx, rx), - ); + #[cfg(not(feature = "connectivity"))] + let can = dp.CAN.can(dp.USB, (tx, rx)); + #[cfg(feature = "connectivity")] + let can = dp.CAN1.can((tx, rx)); // APB1 (PCLK1): 8MHz, Bit rate: 125kBit/s, Sample Point 87.5% // Value was calculated with http://www.bittiming.can-wiki.info/ diff --git a/examples/can-loopback.rs b/examples/can-loopback.rs index 09ca81c2..81fac8c0 100644 --- a/examples/can-loopback.rs +++ b/examples/can-loopback.rs @@ -25,11 +25,10 @@ fn main() -> ! { // resonator must be used. rcc.cfgr.use_hse(8.MHz()).freeze(&mut flash.acr); - let can = Can::<_, Floating>::new_loopback( - dp.CAN1, - #[cfg(not(feature = "connectivity"))] - dp.USB, - ); + #[cfg(not(feature = "connectivity"))] + let can = Can::<_, Floating>::new_loopback(dp.CAN, dp.USB); + #[cfg(feature = "connectivity")] + let can = Can::<_, Floating>::new_loopback(dp.CAN1); // Use loopback mode: No pins need to be assigned to peripheral. // APB1 (PCLK1): 8MHz, Bit rate: 500Bit/s, Sample Point 87.5% diff --git a/examples/can-rtic.rs b/examples/can-rtic.rs index 7a701e65..aae46fa2 100644 --- a/examples/can-rtic.rs +++ b/examples/can-rtic.rs @@ -55,7 +55,11 @@ mod app { use super::{enqueue_frame, PriorityFrame}; use bxcan::{filter::Mask32, ExtendedId, Fifo, Frame, Interrupts, Rx0, StandardId, Tx}; use heapless::binary_heap::{BinaryHeap, Max}; - use stm32f1xx_hal::{can::Can, pac::CAN1, prelude::*}; + #[cfg(not(feature = "connectivity"))] + use stm32f1xx_hal::pac::CAN as CAN1; + #[cfg(feature = "connectivity")] + use stm32f1xx_hal::pac::CAN1; + use stm32f1xx_hal::{can::Can, prelude::*}; #[local] struct Local { @@ -88,7 +92,7 @@ mod app { let can_tx_pin = gpioa.pa12; #[cfg(not(feature = "connectivity"))] - let can = Can::new(cx.device.CAN1, cx.device.USB, (can_tx_pin, can_rx_pin)); + let can = Can::new(cx.device.CAN, cx.device.USB, (can_tx_pin, can_rx_pin)); #[cfg(feature = "connectivity")] let can = Can::new(cx.device.CAN1, (can_tx_pin, can_rx_pin)); diff --git a/src/afio.rs b/src/afio.rs index 80c8bbb1..8eb32b35 100644 --- a/src/afio.rs +++ b/src/afio.rs @@ -215,7 +215,7 @@ remap! { #[cfg(feature = "stm32f103")] remap! { - pac::CAN1: MAPR, u8: can_remap, { 0 | 2 | 3 }; + pac::CAN: MAPR, u8: can_remap, { 0 | 2 | 3 }; } #[cfg(feature = "connectivity")] @@ -303,7 +303,11 @@ pub mod can1 { ], } - impl CanCommon for pac::CAN1 { + #[cfg(not(feature = "connectivity"))] + use pac::CAN as CAN1; + #[cfg(feature = "connectivity")] + use pac::CAN1; + impl CanCommon for CAN1 { type Tx = Tx; type Rx = Rx; } diff --git a/src/can.rs b/src/can.rs index 05eb2ed6..980c3f05 100644 --- a/src/can.rs +++ b/src/can.rs @@ -58,7 +58,12 @@ impl CanExt for CAN { } pub trait Instance: crate::rcc::Enable + afio::CanCommon {} -impl Instance for pac::CAN1 {} +#[cfg(not(feature = "connectivity"))] +use pac::CAN as CAN1; +#[cfg(feature = "connectivity")] +use pac::CAN1; + +impl Instance for CAN1 {} #[cfg(feature = "connectivity")] impl Instance for pac::CAN2 {} @@ -125,8 +130,8 @@ impl Can { } } -unsafe impl bxcan::Instance for Can { - const REGISTERS: *mut bxcan::RegisterBlock = pac::CAN1::ptr() as *mut _; +unsafe impl bxcan::Instance for Can { + const REGISTERS: *mut bxcan::RegisterBlock = CAN1::ptr() as *mut _; } #[cfg(feature = "connectivity")] @@ -134,9 +139,9 @@ unsafe impl bxcan::Instance for Can { const REGISTERS: *mut bxcan::RegisterBlock = pac::CAN2::ptr() as *mut _; } -unsafe impl bxcan::FilterOwner for Can { +unsafe impl bxcan::FilterOwner for Can { const NUM_FILTER_BANKS: u8 = 28; } #[cfg(feature = "connectivity")] -unsafe impl bxcan::MasterInstance for Can {} +unsafe impl bxcan::MasterInstance for Can {} diff --git a/src/flash.rs b/src/flash.rs index ca8e8013..6316b9d6 100644 --- a/src/flash.rs +++ b/src/flash.rs @@ -63,7 +63,7 @@ pub struct FlashWriter<'a> { flash_sz: FlashSize, verify: bool, } -impl<'a> FlashWriter<'a> { +impl FlashWriter<'_> { fn unlock(&mut self) -> Result<()> { // Wait for any ongoing operations while self.flash.sr.sr().read().bsy().bit_is_set() {} @@ -245,7 +245,7 @@ impl<'a> FlashWriter<'a> { // Flash is written 16 bits at a time, so combine two bytes to get a // half-word - let hword: u16 = (data[idx] as u16) | (data[idx + 1] as u16) << 8; + let hword: u16 = (data[idx] as u16) | ((data[idx + 1] as u16) << 8); // NOTE(unsafe) Write to FLASH area with no side effects unsafe { core::ptr::write_volatile(write_address, hword) }; diff --git a/src/gpio.rs b/src/gpio.rs index 75b22b52..b5790b6c 100644 --- a/src/gpio.rs +++ b/src/gpio.rs @@ -223,7 +223,7 @@ mod sealed { } } -use crate::pac::gpioa::crl::{CNF0 as Cnf, MODE0 as Mode}; +use crate::pac::gpioa::crl::{CONFIG as Cnf, MODE as Mode}; use sealed::Interruptable; pub(crate) use sealed::PinMode; @@ -519,7 +519,6 @@ impl Pin { before changing its mode to an output to avoid a short spike of an incorrect value */ - #[inline(always)] fn _set_state(&mut self, state: PinState) { match state { diff --git a/src/i2c.rs b/src/i2c.rs index 0d41215a..0711f217 100644 --- a/src/i2c.rs +++ b/src/i2c.rs @@ -282,7 +282,7 @@ impl I2c { fn send_addr(&self, addr: u8, read: bool) { self.i2c .dr() - .write(|w| w.dr().set(addr << 1 | (u8::from(read)))); + .write(|w| w.dr().set((addr << 1) | (u8::from(read)))); } /// Generate STOP condition diff --git a/src/lib.rs b/src/lib.rs index 35e1bbdf..6c1ccc57 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -157,3 +157,18 @@ mod sealed { pub trait Sealed {} } use sealed::Sealed; +use stm32f1::Periph; + +pub trait Ptr { + /// RegisterBlock structure + type RB; + /// Return the pointer to the register block + fn ptr() -> *const Self::RB; +} + +impl Ptr for Periph { + type RB = RB; + fn ptr() -> *const Self::RB { + Self::ptr() + } +} diff --git a/src/rcc.rs b/src/rcc.rs index fccd814c..5fca1e03 100644 --- a/src/rcc.rs +++ b/src/rcc.rs @@ -187,7 +187,6 @@ impl CFGR { /// let mut rcc = dp.RCC.constrain(); /// let clocks = rcc.cfgr.freeze(&mut flash.acr); /// ``` - #[inline(always)] pub fn freeze(self, acr: &mut ACR) -> Clocks { let cfg = Config::from_cfgr(self); diff --git a/src/rcc/enable.rs b/src/rcc/enable.rs index 959da8c3..cf5670e3 100644 --- a/src/rcc/enable.rs +++ b/src/rcc/enable.rs @@ -65,7 +65,7 @@ macro_rules! ahb_bus { #[cfg(feature = "stm32f103")] bus! { ADC2 => (APB2, 10), - CAN1 => (APB1, 25), + CAN => (APB1, 25), } #[cfg(feature = "connectivity")] bus! { diff --git a/src/rtc.rs b/src/rtc.rs index ad279360..b43442a2 100644 --- a/src/rtc.rs +++ b/src/rtc.rs @@ -41,7 +41,6 @@ pub enum RestoredOrNewRtc { [examples/rtc.rs]: https://github.com/stm32-rs/stm32f1xx-hal/blob/v0.7.0/examples/rtc.rs [examples/blinky_rtc.rs]: https://github.com/stm32-rs/stm32f1xx-hal/blob/v0.7.0/examples/blinky_rtc.rs */ - pub struct Rtc { regs: RTC, _clock_source: PhantomData, @@ -360,7 +359,7 @@ impl Rtc { // Wait for the APB1 interface to be ready while !self.regs.crl().read().rsf().bit() {} - self.regs.cnth().read().bits() << 16 | self.regs.cntl().read().bits() + (self.regs.cnth().read().bits() << 16) | self.regs.cntl().read().bits() } /// Enables triggering the RTC interrupt every time the RTC counter is increased diff --git a/src/serial.rs b/src/serial.rs index 856ead86..2ac2f214 100644 --- a/src/serial.rs +++ b/src/serial.rs @@ -96,15 +96,20 @@ use core::sync::atomic::{self, Ordering}; use embedded_dma::{ReadBuffer, WriteBuffer}; use crate::afio::{self, RInto, Rmp}; +#[cfg(any(all(feature = "stm32f103", feature = "high"), feature = "connectivity"))] +use crate::dma::dma2; use crate::dma::{self, dma1, CircBuffer, RxDma, Transfer, TxDma}; use crate::gpio::{Floating, PushPull, UpMode}; use crate::pac::{self, RCC}; use crate::rcc::{BusClock, Clocks, Enable, Reset}; use crate::time::{Bps, U32Ext}; +pub mod ext; mod hal_02; mod hal_1; +use ext::{SrR, UartExt}; + pub trait SerialExt: Sized + Instance { fn serial( self, @@ -159,28 +164,56 @@ impl SerialExt for USART { } } -use crate::pac::usart1 as uart_base; +pub trait RBExt: UartExt { + fn set_stopbits(&self, bits: StopBits); +} + +impl RBExt for pac::usart1::RegisterBlock { + fn set_stopbits(&self, bits: StopBits) { + use crate::pac::usart1::cr2::STOP; + + self.cr2().write(|w| { + w.stop().variant(match bits { + StopBits::STOP0P5 => STOP::Stop0p5, + StopBits::STOP1 => STOP::Stop1, + StopBits::STOP1P5 => STOP::Stop1p5, + StopBits::STOP2 => STOP::Stop2, + }) + }); + } +} + +#[cfg(any(all(feature = "stm32f103", feature = "high"), feature = "connectivity"))] +impl RBExt for pac::uart4::RegisterBlock { + fn set_stopbits(&self, bits: StopBits) { + use crate::pac::uart4::cr2::STOP; + + // StopBits::STOP0P5 and StopBits::STOP1P5 aren't supported when using UART + // STOP_A::STOP1 and STOP_A::STOP2 will be used, respectively + self.cr2().write(|w| { + w.stop().variant(match bits { + StopBits::STOP0P5 | StopBits::STOP1 => STOP::Stop1, + StopBits::STOP1P5 | StopBits::STOP2 => STOP::Stop2, + }) + }); + } +} pub trait Instance: crate::Sealed - + Deref + + crate::Ptr + + Deref + Enable + Reset + BusClock + afio::SerialAsync { - #[doc(hidden)] - fn ptr() -> *const uart_base::RegisterBlock; } macro_rules! inst { ($($USARTX:ty;)+) => { $( - impl Instance for $USARTX { - fn ptr() -> *const uart_base::RegisterBlock { - <$USARTX>::ptr() - } - } + impl Instance for $USARTX { } )+ }; } @@ -190,6 +223,11 @@ inst! { pac::USART2; pac::USART3; } +#[cfg(any(all(feature = "stm32f103", feature = "high"), feature = "connectivity"))] +inst! { + pac::UART4; + pac::UART5; +} /// Serial error #[derive(Debug)] @@ -519,7 +557,7 @@ fn apply_config(config: Config, clocks: &Clocks) { // Configure baud rate let brr = USART::clock(clocks).raw() / config.baudrate.0; assert!(brr >= 16, "impossible baud rate"); - usart.brr().write(|w| unsafe { w.bits(brr) }); + usart.brr().write(|w| unsafe { w.bits(brr as u16) }); // Configure word usart.cr1().modify(|_r, w| { @@ -537,13 +575,7 @@ fn apply_config(config: Config, clocks: &Clocks) { }); // Configure stop bits - let stop_bits = match config.stopbits { - StopBits::STOP1 => 0b00, - StopBits::STOP0P5 => 0b01, - StopBits::STOP2 => 0b10, - StopBits::STOP1P5 => 0b11, - }; - usart.cr2().modify(|_r, w| w.stop().set(stop_bits)); + usart.set_stopbits(config.stopbits); } /// Reconfigure the USART instance. @@ -657,7 +689,7 @@ impl Rx { Some(Error::Parity) } else if sr.fe().bit_is_set() { Some(Error::FrameFormat) - } else if sr.ne().bit_is_set() { + } else if sr.nf().bit_is_set() { Some(Error::Noise) } else if sr.ore().bit_is_set() { Some(Error::Overrun) @@ -1002,3 +1034,11 @@ serialdma! { rx: dma1::C3, tx: dma1::C2 } +#[cfg(any(all(feature = "stm32f103", feature = "high"), feature = "connectivity"))] +serialdma! { + pac::UART4, + RxDma4, + TxDma4, + rx: dma2::C3, + tx: dma2::C5 +} diff --git a/src/serial/ext.rs b/src/serial/ext.rs new file mode 100644 index 00000000..c8d3829c --- /dev/null +++ b/src/serial/ext.rs @@ -0,0 +1,315 @@ +#![allow(unused)] + +use crate::{sealed, Sealed}; + +use crate::pac::uart4; +use crate::pac::usart1; +use stm32f1::{Readable, Reg, RegisterSpec, Resettable, Writable, R, W}; + +pub trait UartExt: Sealed { + fn cr1(&self) -> &usart1::CR1; + fn dr(&self) -> &usart1::DR; + fn brr(&self) -> &usart1::BRR; + type SRrs: reg::SrR + reg::SrW; + fn sr(&self) -> &Reg; + type CR2rs: reg::Cr2R + reg::Cr2W; + fn cr2(&self) -> &Reg; + type CR3rs: reg::Cr3R + reg::Cr3W; + fn cr3(&self) -> &Reg; + type GTPRrs: reg::GtprR + reg::GtprW; + fn gtpr(&self) -> &Reg; +} + +macro_rules! wrap_r { + (pub trait $TrR:ident { + $(fn $f:ident(&self $(, $n:ident: u8)?) -> $fr:path;)* + }) => { + pub trait $TrR { + $(fn $f(&self $(, $n: u8)?) -> $fr;)* + } + impl $TrR for R { + $( + #[inline(always)] + fn $f(&self $(, $n: u8)?) -> $fr { + REG::$f(self $(, $n)?) + } + )* + } + }; +} + +macro_rules! wrap_w { + (pub trait $TrR:ident { + $(fn $f:ident(&mut self $(, $n:ident: u8)?) -> $fr:path;)* + }) => { + pub trait $TrR { + $(fn $f(&mut self $(, $n: u8)?) -> $fr;)* + } + + impl $TrR for W { + $( + #[inline(always)] + fn $f(&mut self $(, $n: u8)?) -> $fr { + REG::$f(self $(, $n)?) + } + )* + } + }; +} + +wrap_r! { + pub trait SrR { + fn pe(&self) -> usart1::sr::PE_R; + fn fe(&self) -> usart1::sr::FE_R; + fn nf(&self) -> usart1::sr::NE_R; + fn ore(&self) -> usart1::sr::ORE_R; + fn idle(&self) -> usart1::sr::IDLE_R; + fn rxne(&self) -> usart1::sr::RXNE_R; + fn tc(&self) -> usart1::sr::TC_R; + fn txe(&self) -> usart1::sr::TXE_R; + fn lbd(&self) -> usart1::sr::LBD_R; + } +} +wrap_w! { + pub trait SrW { + fn rxne(&mut self) -> usart1::sr::RXNE_W; + fn tc(&mut self) -> usart1::sr::TC_W; + fn lbd(&mut self) -> usart1::sr::LBD_W; + } +} + +wrap_r! { + pub trait Cr2R { + fn add(&self) -> usart1::cr2::ADD_R; + fn lbdl(&self) -> usart1::cr2::LBDL_R; + fn lbdie(&self) -> usart1::cr2::LBDIE_R; + fn linen(&self) -> usart1::cr2::LINEN_R; + } +} +wrap_w! { + pub trait Cr2W { + fn add(&mut self) -> usart1::cr2::ADD_W; + fn lbdl(&mut self) -> usart1::cr2::LBDL_W; + fn lbdie(&mut self) -> usart1::cr2::LBDIE_W; + fn linen(&mut self) -> usart1::cr2::LINEN_W; + } +} + +wrap_r! { + pub trait Cr3R { + fn eie(&self) -> usart1::cr3::EIE_R; + fn iren(&self) -> usart1::cr3::IREN_R; + fn irlp(&self) -> usart1::cr3::IRLP_R; + fn hdsel(&self) -> usart1::cr3::HDSEL_R; + fn dmar(&self) -> usart1::cr3::DMAR_R; + fn dmat(&self) -> usart1::cr3::DMAT_R; + } +} +wrap_w! { + pub trait Cr3W { + fn eie(&mut self) -> usart1::cr3::EIE_W; + fn iren(&mut self) -> usart1::cr3::IREN_W; + fn irlp(&mut self) -> usart1::cr3::IRLP_W; + fn hdsel(&mut self) -> usart1::cr3::HDSEL_W; + fn dmar(&mut self) -> usart1::cr3::DMAR_W; + fn dmat(&mut self) -> usart1::cr3::DMAT_W; + } +} + +wrap_r! { + pub trait GtprR { + fn psc(&self) -> usart1::gtpr::PSC_R; + } +} +wrap_w! { + pub trait GtprW { + fn psc(&mut self) -> usart1::gtpr::PSC_W; + } +} + +mod reg { + use super::*; + + pub trait SrR: RegisterSpec + Readable + Sized { + fn pe(r: &R) -> usart1::sr::PE_R; + fn fe(r: &R) -> usart1::sr::FE_R; + fn nf(r: &R) -> usart1::sr::NE_R; + fn ore(r: &R) -> usart1::sr::ORE_R; + fn idle(r: &R) -> usart1::sr::IDLE_R; + fn rxne(r: &R) -> usart1::sr::RXNE_R; + fn tc(r: &R) -> usart1::sr::TC_R; + fn txe(r: &R) -> usart1::sr::TXE_R; + fn lbd(r: &R) -> usart1::sr::LBD_R; + } + pub trait SrW: RegisterSpec + Writable + Resettable + Sized { + fn rxne(w: &mut W) -> usart1::sr::RXNE_W; + fn tc(w: &mut W) -> usart1::sr::TC_W; + fn lbd(w: &mut W) -> usart1::sr::LBD_W; + } + + pub trait Cr2R: RegisterSpec + Readable + Sized { + fn add(r: &R) -> usart1::cr2::ADD_R; + fn lbdl(r: &R) -> usart1::cr2::LBDL_R; + fn lbdie(r: &R) -> usart1::cr2::LBDIE_R; + fn linen(r: &R) -> usart1::cr2::LINEN_R; + } + pub trait Cr2W: RegisterSpec + Writable + Resettable + Sized { + fn add(w: &mut W) -> usart1::cr2::ADD_W; + fn lbdl(w: &mut W) -> usart1::cr2::LBDL_W; + fn lbdie(w: &mut W) -> usart1::cr2::LBDIE_W; + fn linen(w: &mut W) -> usart1::cr2::LINEN_W; + } + + pub trait Cr3R: RegisterSpec + Readable + Sized { + fn eie(r: &R) -> usart1::cr3::EIE_R; + fn iren(r: &R) -> usart1::cr3::IREN_R; + fn irlp(r: &R) -> usart1::cr3::IRLP_R; + fn hdsel(r: &R) -> usart1::cr3::HDSEL_R; + fn dmar(r: &R) -> usart1::cr3::DMAR_R; + fn dmat(r: &R) -> usart1::cr3::DMAT_R; + } + pub trait Cr3W: RegisterSpec + Writable + Resettable + Sized { + fn eie(w: &mut W) -> usart1::cr3::EIE_W; + fn iren(w: &mut W) -> usart1::cr3::IREN_W; + fn irlp(w: &mut W) -> usart1::cr3::IRLP_W; + fn hdsel(w: &mut W) -> usart1::cr3::HDSEL_W; + fn dmar(w: &mut W) -> usart1::cr3::DMAR_W; + fn dmat(w: &mut W) -> usart1::cr3::DMAT_W; + } + + pub trait GtprR: RegisterSpec + Readable + Sized { + fn psc(r: &R) -> usart1::gtpr::PSC_R; + } + pub trait GtprW: RegisterSpec + Writable + Resettable + Sized { + fn psc(w: &mut W) -> usart1::gtpr::PSC_W; + } +} + +macro_rules! impl_reg { + ($($r:ident -> &$rty:path;)*) => { + $( + #[inline(always)] + fn $r(&self) -> &$rty { + self.$r() + } + )* + }; +} + +macro_rules! impl_read { + ($($f:ident $(: $n:ident)? -> $fty:path;)*) => { + $( + #[inline(always)] + fn $f(r: &R $(, $n: u8)?) -> $fty { + r.$f($($n)?) + } + )* + }; +} +macro_rules! impl_write { + ($($f:ident $(: $n:ident)? -> $fty:path;)*) => { + $( + #[inline(always)] + fn $f(w: &mut W $(, $n: u8)?) -> $fty { + w.$f($($n)?) + } + )* + }; +} + +macro_rules! impl_ext { + ($(#[$attr:meta])* $uart:ident) => { + impl Sealed for $uart::RegisterBlock {} + impl UartExt for $uart::RegisterBlock { + type SRrs = $uart::sr::SRrs; + type CR2rs = $uart::cr2::CR2rs; + type CR3rs = $uart::cr3::CR3rs; + type GTPRrs = $uart::gtpr::GTPRrs; + impl_reg! { + cr1 -> &usart1::CR1; + dr -> &usart1::DR; + brr -> &usart1::BRR; + sr -> &Reg; + cr2 -> &Reg; + cr3 -> &Reg; + gtpr -> &Reg; + } + } + + impl reg::SrR for $uart::sr::SRrs { + impl_read! { + pe -> usart1::sr::PE_R; + fe -> usart1::sr::FE_R; + nf -> usart1::sr::NE_R; + ore -> usart1::sr::ORE_R; + idle -> usart1::sr::IDLE_R; + rxne -> usart1::sr::RXNE_R; + tc -> usart1::sr::TC_R; + txe -> usart1::sr::TXE_R; + lbd -> usart1::sr::LBD_R; + } + } + impl reg::SrW for $uart::sr::SRrs { + impl_write! { + rxne -> usart1::sr::RXNE_W; + tc -> usart1::sr::TC_W; + lbd -> usart1::sr::LBD_W; + } + } + + impl reg::Cr2R for $uart::cr2::CR2rs { + impl_read! { + add -> usart1::cr2::ADD_R; + lbdl -> usart1::cr2::LBDL_R; + lbdie -> usart1::cr2::LBDIE_R; + linen -> usart1::cr2::LINEN_R; + } + } + impl reg::Cr2W for $uart::cr2::CR2rs { + impl_write! { + add -> usart1::cr2::ADD_W; + lbdl -> usart1::cr2::LBDL_W; + lbdie -> usart1::cr2::LBDIE_W; + linen -> usart1::cr2::LINEN_W; + } + } + + $(#[$attr])* + impl reg::Cr3R for $uart::cr3::CR3rs { + impl_read! { + eie -> usart1::cr3::EIE_R; + iren -> usart1::cr3::IREN_R; + irlp -> usart1::cr3::IRLP_R; + hdsel -> usart1::cr3::HDSEL_R; + dmar -> usart1::cr3::DMAR_R; + dmat -> usart1::cr3::DMAT_R; + } + } + $(#[$attr])* + impl reg::Cr3W for $uart::cr3::CR3rs { + impl_write! { + eie -> usart1::cr3::EIE_W; + iren -> usart1::cr3::IREN_W; + irlp -> usart1::cr3::IRLP_W; + hdsel -> usart1::cr3::HDSEL_W; + dmar -> usart1::cr3::DMAR_W; + dmat -> usart1::cr3::DMAT_W; + } + } + + impl reg::GtprR for $uart::gtpr::GTPRrs { + impl_read! { + psc -> usart1::gtpr::PSC_R; + } + } + impl reg::GtprW for $uart::gtpr::GTPRrs { + impl_write! { + psc -> usart1::gtpr::PSC_W; + } + } + }; +} + +impl_ext!(usart1); +#[cfg(any(all(feature = "stm32f103", feature = "high"), feature = "connectivity"))] +impl_ext!(uart4);