diff --git a/Cargo.toml b/Cargo.toml index 30065321..2491f4f6 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -55,6 +55,7 @@ disable-linker-script = [] # STM32L0 subfamilies # (Warning: Some peripherals, e.g. GPIO, don't follow this subfamily grouping.) +stm32l0x0 = ["stm32l0/stm32l0x0"] stm32l0x1 = ["stm32l0/stm32l0x1"] stm32l0x2 = ["stm32l0/stm32l0x2"] stm32l0x3 = ["stm32l0/stm32l0x3"] @@ -337,7 +338,7 @@ required-features = ["stm32l0x2", "io-STM32L071"] [[example]] name = "serial" -required-features = ["stm32l0x2", "io-STM32L071"] +# required-features = ["stm32l0x2", "io-STM32L071"] [[example]] name = "serial_dma" diff --git a/build.rs b/build.rs index 90efb0d1..c7e17c3b 100644 --- a/build.rs +++ b/build.rs @@ -9,6 +9,10 @@ fn main() { let mut feature_count = 0; + if cfg!(feature = "stm32l0x0") { + feature_count += 1; + } + if cfg!(feature = "stm32l0x1") { feature_count += 1; } @@ -22,11 +26,13 @@ fn main() { } if feature_count != 1 { - panic!("\n\nMust select exactly one package for linker script generation!\nChoices: 'stm32l0x1' or 'stm32l0x2' or 'stm32l0x3'\nAlternatively, pick the mcu-feature that matches your MCU, for example 'mcu-STM32L071KBTx'\n\n"); + panic!("\n\nMust select exactly one package for linker script generation!\nChoices: 'stm32l0x0' or 'stm32l0x1' or 'stm32l0x2' or 'stm32l0x3'\nAlternatively, pick the mcu-feature that matches your MCU, for example 'mcu-STM32L071KBTx'\n\n"); } if !cfg!(feature = "disable-linker-script") { - let linker = if cfg!(feature = "stm32l0x1") { + let linker = if cfg!(feature = "stm32l0x0") { + include_bytes!("memory_l0x0.x").as_ref() + } else if cfg!(feature = "stm32l0x1") { include_bytes!("memory_l0x1.x").as_ref() } else if cfg!(feature = "stm32l0x2") { include_bytes!("memory_l0x2.x").as_ref() @@ -42,6 +48,7 @@ fn main() { .unwrap(); println!("cargo:rustc-link-search={}", out.display()); + println!("cargo:rerun-if-changed=memory_l0x0.x"); println!("cargo:rerun-if-changed=memory_l0x1.x"); println!("cargo:rerun-if-changed=memory_l0x2.x"); println!("cargo:rerun-if-changed=memory_l0x3.x"); diff --git a/examples/blinky.rs b/examples/blinky.rs index 1aeb8053..0da97ce0 100644 --- a/examples/blinky.rs +++ b/examples/blinky.rs @@ -16,10 +16,10 @@ fn main() -> ! { // Acquire the GPIOA peripheral. This also enables the clock for GPIOA in // the RCC register. - let gpioa = dp.GPIOA.split(&mut rcc); + let gpioc = dp.GPIOC.split(&mut rcc); // Configure PA1 as output. - let mut led = gpioa.pa1.into_push_pull_output(); + let mut led = gpioc.pc1.into_push_pull_output(); loop { // Set the LED high one million times in a row. diff --git a/examples/blinky_delay.rs b/examples/blinky_delay.rs index cd143af6..a3dc1517 100644 --- a/examples/blinky_delay.rs +++ b/examples/blinky_delay.rs @@ -16,10 +16,10 @@ fn main() -> ! { // Acquire the GPIOA peripheral. This also enables the clock for GPIOA in // the RCC register. - let gpioa = dp.GPIOA.split(&mut rcc); + let gpioa = dp.GPIOC.split(&mut rcc); // Configure PA1 as output. - let mut led = gpioa.pa1.into_push_pull_output(); + let mut led = gpioa.pc1.into_push_pull_output(); // Get the delay provider. let mut delay = cp.SYST.delay(rcc.clocks); @@ -29,6 +29,6 @@ fn main() -> ! { delay.delay_ms(500_u16); led.set_low().unwrap(); - delay.delay_ms(500_u16); + delay.delay_ms(2000_u16); } } diff --git a/examples/lptim.rs b/examples/lptim.rs index 9bf0882a..f8bc360e 100644 --- a/examples/lptim.rs +++ b/examples/lptim.rs @@ -10,7 +10,7 @@ use cortex_m_rt::entry; use nb::block; use stm32l0xx_hal::{ exti::{DirectLine, Exti}, - gpio::{gpiob::PB, Output, PushPull}, + gpio::{gpioc::PC, Output, PushPull}, lptim::{self, ClockSrc, LpTimer}, pac, prelude::*, @@ -27,11 +27,11 @@ fn main() -> ! { let mut rcc = dp.RCC.freeze(rcc::Config::msi(rcc::MSIRange::Range0)); let mut exti = Exti::new(dp.EXTI); let mut pwr = PWR::new(dp.PWR, &mut rcc); - let gpiob = dp.GPIOB.split(&mut rcc); + let gpioc = dp.GPIOC.split(&mut rcc); - let mut led = gpiob.pb2.into_push_pull_output().downgrade(); + let mut led = gpioc.pc1.into_push_pull_output().downgrade(); - let mut lptim = LpTimer::init_periodic(dp.LPTIM, &mut pwr, &mut rcc, ClockSrc::Lse); + let mut lptim = LpTimer::init_periodic(dp.LPTIM, &mut pwr, &mut rcc, ClockSrc::Lsi); let exti_line = DirectLine::Lptim1; @@ -105,7 +105,7 @@ fn main() -> ! { } } -fn blink(led: &mut PB>) { +fn blink(led: &mut PC>) { led.set_high().unwrap(); delay(); led.set_low().unwrap(); diff --git a/examples/pwm.rs b/examples/pwm.rs index 3a6ac2a2..bbb6dae6 100644 --- a/examples/pwm.rs +++ b/examples/pwm.rs @@ -26,7 +26,7 @@ fn main() -> ! { // Initialize TIM2 for PWM let pwm = pwm::Timer::new(dp.TIM2, 10.khz(), &mut rcc); - #[cfg(feature = "stm32l0x1")] + #[cfg(any(feature = "stm32l0x0", feature = "stm32l0x1"))] let mut pwm = pwm.channel2.assign(gpioa.pa1); // This is LD2 on ST's B-L072Z-LRWAN1 development board. diff --git a/examples/timer.rs b/examples/timer.rs index daca5ca9..06385ad5 100644 --- a/examples/timer.rs +++ b/examples/timer.rs @@ -18,7 +18,7 @@ use stm32l0xx_hal::{ timer::Timer, }; -static LED: Mutex>>>> = Mutex::new(RefCell::new(None)); +static LED: Mutex>>>> = Mutex::new(RefCell::new(None)); static TIMER: Mutex>>> = Mutex::new(RefCell::new(None)); #[entry] @@ -30,10 +30,10 @@ fn main() -> ! { // Acquire the GPIOA peripheral. This also enables the clock for GPIOA in // the RCC register. - let gpioa = dp.GPIOA.split(&mut rcc); + let gpioc = dp.GPIOC.split(&mut rcc); // Configure PA1 as output. - let led = gpioa.pa1.into_push_pull_output(); + let led = gpioc.pc1.into_push_pull_output(); // Configure the timer. let mut timer = dp.TIM2.timer(1.hz(), &mut rcc); diff --git a/examples/timer_interrupt_rtic.rs b/examples/timer_interrupt_rtic.rs index 554a1dba..d616814f 100644 --- a/examples/timer_interrupt_rtic.rs +++ b/examples/timer_interrupt_rtic.rs @@ -11,7 +11,7 @@ use stm32l0xx_hal::{gpio::*, pac, prelude::*, rcc::Config, timer::Timer}; #[app(device = stm32l0xx_hal::pac, peripherals = true)] const APP: () = { struct Resources { - led: gpioa::PA>, + led: gpioc::PC>, timer: Timer, } @@ -24,13 +24,13 @@ const APP: () = { // Acquire the GPIOA peripheral. This also enables the clock for GPIOA // in the RCC register. - let gpioa = device.GPIOA.split(&mut rcc); + let gpioc = device.GPIOC.split(&mut rcc); // Configure PA1 as output. - let led = gpioa.pa1.into_push_pull_output().downgrade(); + let led = gpioc.pc1.into_push_pull_output().downgrade(); // Configure the timer. - let mut timer = device.TIM2.timer(1.hz(), &mut rcc); + let mut timer = device.TIM2.timer(8.hz(), &mut rcc); timer.listen(); // Return the initialised resources. diff --git a/memory_l0x0.x b/memory_l0x0.x new file mode 100644 index 00000000..e20ff2b1 --- /dev/null +++ b/memory_l0x0.x @@ -0,0 +1,5 @@ +MEMORY +{ + FLASH : ORIGIN = 0x08000000, LENGTH = 128K + RAM : ORIGIN = 0x20000000, LENGTH = 20K +} diff --git a/src/dma.rs b/src/dma.rs index ccaad295..181de6b4 100644 --- a/src/dma.rs +++ b/src/dma.rs @@ -26,7 +26,7 @@ use crate::{ rcc::Rcc, }; -#[cfg(any(feature = "io-STM32L051", feature = "io-STM32L071"))] +#[cfg(all(not(feature = "stm32l0x0"), any(feature = "io-STM32L051", feature = "io-STM32L071")))] use crate::pac::USART1; #[cfg(any( @@ -37,9 +37,16 @@ use crate::pac::USART1; ))] use crate::{ i2c, - pac::{I2C1, I2C2, I2C3, USART2}, + pac::{I2C1, USART2}, serial, }; +#[cfg(not(feature = "stm32l0x0"))] +use crate::{ + pac::{ + I2C2, + I2C3 + }, +}; use crate::{pac::SPI1, spi}; @@ -329,14 +336,14 @@ macro_rules! impl_channel { handle: &mut Handle, address: u32, ) { - handle.dma.$chfield.par.write(|w| w.pa().bits(address)); + unsafe { handle.dma.$chfield.par.write(|w| w.pa().bits(address)); } } fn set_memory_address(&self, handle: &mut Handle, address: u32, ) { - handle.dma.$chfield.mar.write(|w| w.ma().bits(address)); + unsafe { handle.dma.$chfield.mar.write(|w| w.ma().bits(address)); } } fn set_transfer_len(&self, handle: &mut Handle, len: u16) { @@ -509,7 +516,7 @@ impl_target!( adc::DmaToken, Channel2, 0; ); -#[cfg(any(feature = "io-STM32L051", feature = "io-STM32L071"))] +#[cfg(all(not(feature = "stm32l0x0"), any(feature = "io-STM32L051", feature = "io-STM32L071")))] impl_target!( // USART1 serial::Tx, Channel2, 3; diff --git a/src/exti.rs b/src/exti.rs index 4c04de6f..d3b07dfa 100755 --- a/src/exti.rs +++ b/src/exti.rs @@ -308,11 +308,14 @@ impl ExtiLine for GpioLine { /// both. #[derive(Copy, Clone, PartialEq, Eq)] pub enum ConfigurableLine { + #[cfg(not(feature = "stm32l0x0"))] Pvd = 16, RtcAlarm = 17, RtcTamper_CssLse = 19, RtcWakeup = 20, + #[cfg(not(feature = "stm32l0x0"))] Comp1 = 21, + #[cfg(not(feature = "stm32l0x0"))] Comp2 = 22, } @@ -321,12 +324,15 @@ impl ExtiLine for ConfigurableLine { use ConfigurableLine::*; Some(match line { + #[cfg(not(feature = "stm32l0x0"))] 16 => Pvd, 17 => RtcAlarm, // 18 = USB (or reserved) 19 => RtcTamper_CssLse, 20 => RtcWakeup, + #[cfg(not(feature = "stm32l0x0"))] 21 => Comp1, + #[cfg(not(feature = "stm32l0x0"))] 22 => Comp2, _ => return None, }) @@ -341,8 +347,10 @@ impl ExtiLine for ConfigurableLine { use ConfigurableLine::*; match self { + #[cfg(not(feature = "stm32l0x0"))] Pvd => Interrupt::PVD, RtcAlarm | RtcTamper_CssLse | RtcWakeup => Interrupt::RTC, + #[cfg(not(feature = "stm32l0x0"))] Comp1 | Comp2 => Interrupt::ADC_COMP, } } @@ -354,7 +362,9 @@ pub enum DirectLine { #[cfg(any(feature = "stm32l0x2", feature = "stm32l0x3"))] Usb = 18, I2C1 = 23, + #[cfg(not(feature = "stm32l0x0"))] I2C3 = 24, + #[cfg(not(feature = "stm32l0x0"))] Usart1 = 25, Usart2 = 26, // 27 = reserved @@ -370,7 +380,9 @@ impl ExtiLine for DirectLine { #[cfg(any(feature = "stm32l0x2", feature = "stm32l0x3"))] 18 => Usb, 23 => I2C1, + #[cfg(not(feature = "stm32l0x0"))] 24 => I2C3, + #[cfg(not(feature = "stm32l0x0"))] 25 => Usart1, 26 => Usart2, // 27 = reserved @@ -392,9 +404,14 @@ impl ExtiLine for DirectLine { #[cfg(any(feature = "stm32l0x2", feature = "stm32l0x3"))] Usb => Interrupt::USB, I2C1 => Interrupt::I2C1, + #[cfg(not(feature = "stm32l0x0"))] I2C3 => Interrupt::I2C3, + #[cfg(not(feature = "stm32l0x0"))] Usart1 => Interrupt::USART1, Usart2 => Interrupt::USART2, + #[cfg(feature = "stm32l0x0")] + Lpuart1 => Interrupt::LPUART1, + #[cfg(not(feature = "stm32l0x0"))] Lpuart1 => Interrupt::AES_RNG_LPUART1, Lptim1 => Interrupt::LPTIM1, } diff --git a/src/gpio.rs b/src/gpio.rs index 9f9d4214..693c13ee 100755 --- a/src/gpio.rs +++ b/src/gpio.rs @@ -6,16 +6,16 @@ use crate::rcc::Rcc; /// Extension trait to split a GPIO peripheral in independent pins and registers pub trait GpioExt { - /// The parts to split the GPIO into - type Parts; + /// The parts to split the GPIO into + type Parts; - /// Splits the GPIO block into independent pins and registers - fn split(self, rcc: &mut Rcc) -> Self::Parts; + /// Splits the GPIO block into independent pins and registers + fn split(self, rcc: &mut Rcc) -> Self::Parts; } /// Input mode (type state) pub struct Input { - _mode: PhantomData, + _mode: PhantomData, } /// Floating input (type state) @@ -27,6 +27,9 @@ pub struct PullDown; /// Pulled up input (type state) pub struct PullUp; +/// Alternative mode Open drain output (type state) +pub struct AltOpenDrain; + /// Open drain input or output (type state) pub struct OpenDrain; @@ -35,652 +38,742 @@ pub struct Analog; /// Output mode (type state) pub struct Output { - _mode: PhantomData, + _mode: PhantomData, } /// Push pull output (type state) pub struct PushPull; mod sealed { - pub trait Sealed {} + pub trait Sealed {} } /// Marker trait for valid pin modes (type state). /// /// It can not be implemented by outside types. pub trait PinMode: sealed::Sealed { - // These constants are used to implement the pin configuration code. - // They are not part of public API. - - #[doc(hidden)] - const PUPDR: u8; - #[doc(hidden)] - const MODER: u8; - #[doc(hidden)] - const OTYPER: Option = None; + // These constants are used to implement the pin configuration code. + // They are not part of public API. + + #[doc(hidden)] + const PUPDR: u8; + #[doc(hidden)] + const MODER: u8; + #[doc(hidden)] + const OTYPER: Option = None; } impl sealed::Sealed for Input {} impl PinMode for Input { - const PUPDR: u8 = 0b00; - const MODER: u8 = 0b00; + const PUPDR: u8 = 0b00; + const MODER: u8 = 0b00; } impl sealed::Sealed for Input {} impl PinMode for Input { - const PUPDR: u8 = 0b10; - const MODER: u8 = 0b00; + const PUPDR: u8 = 0b10; + const MODER: u8 = 0b00; } impl sealed::Sealed for Input {} impl PinMode for Input { - const PUPDR: u8 = 0b01; - const MODER: u8 = 0b00; + const PUPDR: u8 = 0b01; + const MODER: u8 = 0b00; } impl sealed::Sealed for Analog {} impl PinMode for Analog { - const PUPDR: u8 = 0b00; - const MODER: u8 = 0b11; + const PUPDR: u8 = 0b00; + const MODER: u8 = 0b11; } impl sealed::Sealed for Output {} impl PinMode for Output { - const PUPDR: u8 = 0b00; - const MODER: u8 = 0b01; + const PUPDR: u8 = 0b00; + const MODER: u8 = 0b01; + const OTYPER: Option = Some(0b1); +} + +impl sealed::Sealed for Output {} +impl PinMode for Output { + const PUPDR: u8 = 0b10; + const MODER: u8 = 0b10010; const OTYPER: Option = Some(0b1); } impl sealed::Sealed for Output {} impl PinMode for Output { - const PUPDR: u8 = 0b00; - const MODER: u8 = 0b01; - const OTYPER: Option = Some(0b0); + const PUPDR: u8 = 0b00; + const MODER: u8 = 0b01; + const OTYPER: Option = Some(0b0); } /// GPIO Pin speed selection #[derive(Debug, Copy, Clone, PartialEq, Eq)] pub enum Speed { - Low = 0, - Medium = 1, - High = 2, - VeryHigh = 3, + Low = 0, + Medium = 1, + High = 2, + VeryHigh = 3, } #[allow(dead_code)] pub enum AltMode { - AF0 = 0, - AF1 = 1, - AF2 = 2, - AF3 = 3, - AF4 = 4, - AF5 = 5, - AF6 = 6, - AF7 = 7, + AF0 = 0, + AF1 = 1, + AF2 = 2, + AF3 = 3, + AF4 = 4, + AF5 = 5, + AF6 = 6, + AF7 = 7, } #[derive(Copy, Clone, Debug, PartialEq, Eq)] pub enum Port { - PA, - PB, - PC, - PD, - PE, - PH, + PA, + PB, + PC, + PD, + PE, + PH, } macro_rules! gpio { - ($GPIOX:ident, $gpiox:ident, $iopxenr:ident, $PXx:ident, [ - $($PXi:ident: ($pxi:ident, $i:expr, $MODE:ty),)+ - ]) => { - /// GPIO - pub mod $gpiox { - use core::marker::PhantomData; - - use crate::hal::digital::v2::{toggleable, InputPin, OutputPin, StatefulOutputPin}; - use crate::pac::$GPIOX; - use crate::rcc::Rcc; - use super::{ - Floating, GpioExt, Input, OpenDrain, Output, Speed, - PullDown, PullUp, PushPull, AltMode, Analog, Port, - PinMode, - }; - - /// GPIO parts - pub struct Parts { - $( - /// Pin - pub $pxi: $PXi<$MODE>, - )+ - } - - impl GpioExt for $GPIOX { - type Parts = Parts; - - fn split(self, rcc: &mut Rcc) -> Parts { - rcc.rb.iopenr.modify(|_, w| w.$iopxenr().set_bit()); - - Parts { - $( - $pxi: $PXi { - _mode: PhantomData, - }, - )+ - } - } - } - - /// Partially erased pin - pub struct $PXx { - i: u8, - _mode: PhantomData, - } - - impl $PXx { - /// The port this pin is part of. - pub const PORT: Port = Port::$PXx; - - /// Returns the port this pin is part of. - pub fn port(&self) -> Port { - Port::$PXx - } - - /// Returns this pin's number inside its port. - pub fn pin_number(&self) -> u8 { - self.i - } - } - - impl OutputPin for $PXx> { - type Error = void::Void; - - fn set_high(&mut self) -> Result<(), Self::Error> { - // NOTE(unsafe) atomic write to a stateless register - unsafe { (*$GPIOX::ptr()).bsrr.write(|w| w.bits(1 << self.i)) }; - Ok(()) - } - - fn set_low(&mut self) -> Result<(), Self::Error> { - // NOTE(unsafe) atomic write to a stateless register - unsafe { (*$GPIOX::ptr()).bsrr.write(|w| w.bits(1 << (self.i + 16))) }; - Ok(()) - } - } - - impl StatefulOutputPin for $PXx> { - fn is_set_high(&self) -> Result { - let is_high = self.is_set_low()?; - Ok(is_high) - } - - fn is_set_low(&self) -> Result { - // NOTE(unsafe) atomic read with no side effects - let is_low = unsafe { (*$GPIOX::ptr()).odr.read().bits() & (1 << self.i) == 0 }; - Ok(is_low) - } - } - - impl toggleable::Default for $PXx> {} - - impl InputPin for $PXx> { - type Error = void::Void; - - fn is_high(&self) -> Result { - let is_high = !self.is_low()?; - Ok(is_high) - } - - fn is_low(&self) -> Result { - // NOTE(unsafe) atomic read with no side effects - let is_low = unsafe { (*$GPIOX::ptr()).idr.read().bits() & (1 << self.i) == 0 }; - Ok(is_low) - } - } - - impl InputPin for $PXx> { - type Error = void::Void; - - fn is_high(&self) -> Result { - let is_high = !self.is_low()?; - Ok(is_high) - } - - fn is_low(&self) -> Result { - // NOTE(unsafe) atomic read with no side effects - let is_low = unsafe { (*$GPIOX::ptr()).idr.read().bits() & (1 << self.i) == 0 }; - Ok(is_low) - } - } - - $( - /// Pin - pub struct $PXi { - _mode: PhantomData, - } - - impl $PXi { - /// The port this pin is part of. - pub const PORT: Port = Port::$PXx; - - /// The pin's number inside its port. - pub const PIN_NUMBER: u8 = $i; - - /// Returns the port this pin is part of. - pub fn port(&self) -> Port { - Port::$PXx - } - - /// Returns this pin's number inside its port. - pub fn pin_number(&self) -> u8 { - $i - } - } - - impl $PXi { - /// Puts `self` into mode `M`. - /// - /// This violates the type state constraints from `MODE`, so callers must - /// ensure they use this properly. - fn mode(&mut self) { - let offset = 2 * $i; - unsafe { - &(*$GPIOX::ptr()).pupdr.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (u32::from(M::PUPDR) << offset)) - }); - - if let Some(otyper) = M::OTYPER { - &(*$GPIOX::ptr()).otyper.modify(|r, w| { - w.bits(r.bits() & !(0b1 << $i) | (u32::from(otyper) << $i)) - }); - } - - &(*$GPIOX::ptr()).moder.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (u32::from(M::MODER) << offset)) - }); - } - } - - fn with_mode( - &mut self, - f: F - ) -> R - where - M: PinMode, - F: FnOnce(&mut $PXi) -> R, - { - struct ResetMode<'a, ORIG: PinMode> { - pin: &'a mut $PXi, - } - - impl<'a, ORIG: PinMode> Drop for ResetMode<'a, ORIG> { - fn drop(&mut self) { - self.pin.mode::(); - } - } - - self.mode::(); - - // This will reset the pin back to the original mode when dropped. - // (so either when `with_mode` returns or when `f` unwinds) - let _resetti = ResetMode { pin: self }; - - let mut witness = $PXi { - _mode: PhantomData - }; - - f(&mut witness) - } - - /// Configures the pin to operate as a floating input pin. - pub fn into_floating_input( - mut self, - ) -> $PXi> { - self.mode::>(); - $PXi { - _mode: PhantomData - } - } - - /// Temporarily configures this pin as a floating input. - /// - /// The closure `f` is called with the reconfigured pin. After it returns, - /// the pin will be configured back. - pub fn with_floating_input( - &mut self, - f: impl FnOnce(&mut $PXi>) -> R, - ) -> R { - self.with_mode(f) - } - - /// Configures the pin to operate as a pulled-down input pin. - pub fn into_pull_down_input( - mut self, - ) -> $PXi> { - self.mode::>(); - $PXi { - _mode: PhantomData - } - } - - /// Temporarily configures this pin as a pulled-down input. - /// - /// The closure `f` is called with the reconfigured pin. After it returns, - /// the pin will be configured back. - pub fn with_pull_down_input( - &mut self, - f: impl FnOnce(&mut $PXi>) -> R, - ) -> R { - self.with_mode(f) - } - - /// Configures the pin to operate as a pulled-up input pin. - pub fn into_pull_up_input( - mut self, - ) -> $PXi> { - self.mode::>(); - $PXi { - _mode: PhantomData - } - } - - /// Temporarily configures this pin as a pulled-up input. - /// - /// The closure `f` is called with the reconfigured pin. After it returns, - /// the pin will be configured back. - pub fn with_pull_up_input( - &mut self, - f: impl FnOnce(&mut $PXi>) -> R, - ) -> R { - self.with_mode(f) - } - - /// Configures the pin to operate as an analog pin. - pub fn into_analog( - mut self, - ) -> $PXi { - self.mode::(); - $PXi { - _mode: PhantomData - } - } - - /// Temporarily configures this pin as an analog pin. - /// - /// The closure `f` is called with the reconfigured pin. After it returns, - /// the pin will be configured back. - pub fn with_analog( - &mut self, - f: impl FnOnce(&mut $PXi) -> R, - ) -> R { - self.with_mode(f) - } + ($GPIOX:ident, $gpiox:ident, $gpioy:ident, $iopxenr:ident, $iopxrst:ident, $PXx:ident, [ + $($PXi:ident: ($pxi:ident, $i:expr, $MODE:ty, $AFR:ident),)+ + ]) => { + /// GPIO + pub mod $gpiox { + use core::marker::PhantomData; + + use crate::hal::digital::v2::{toggleable, InputPin, OutputPin, StatefulOutputPin}; + use crate::pac::{$GPIOX, $gpioy}; + use crate::rcc::{Rcc}; + use super::{ + Floating, GpioExt, Input, OpenDrain, Output, Speed, + PullDown, PullUp, PushPull, AltMode, Analog, Port, + PinMode, AltOpenDrain, + }; + + /// GPIO parts + pub struct Parts { + /// Opaque AFRH register + pub afrh: AFRH, + /// Opaque AFRL register + pub afrl: AFRL, + /// Opaque MODER register + pub moder: MODER, + /// Opaque OTYPER register + pub otyper: OTYPER, + /// Opaque PUPDR register + pub pupdr: PUPDR, + $( + /// Pin + pub $pxi: $PXi<$MODE>, + )+ + } + impl GpioExt for $GPIOX { + type Parts = Parts; + + fn split(self, rcc: &mut Rcc) -> Parts { + rcc.iopenr.enr().modify(|_, w| w.$iopxenr().enabled()); + rcc.ioprstr.rstr().modify(|_, w| w.$iopxrst().set_bit()); + rcc.ioprstr.rstr().modify(|_, w| w.$iopxrst().clear_bit()); + + Parts { + afrh: AFRH { _0: () }, + afrl: AFRL { _0: () }, + moder: MODER { _0: () }, + otyper: OTYPER { _0: () }, + pupdr: PUPDR { _0: () }, + $( + $pxi: $PXi { _mode: PhantomData }, + )+ + } + } + } + + /// Opaque AFRL register + pub struct AFRL { + _0: (), + } + + impl AFRL { + pub(crate) fn afr(&mut self) -> &$gpioy::AFRL { + unsafe { &(*$GPIOX::ptr()).afrl } + } + } + + /// Opaque AFRH register + pub struct AFRH { + _0: (), + } + + impl AFRH { + pub(crate) fn afr(&mut self) -> &$gpioy::AFRH { + unsafe { &(*$GPIOX::ptr()).afrh } + } + } + + /// Opaque MODER register + pub struct MODER { + _0: (), + } + + impl MODER { + pub(crate) fn moder(&mut self) -> &$gpioy::MODER { + unsafe { &(*$GPIOX::ptr()).moder } + } + } + + /// Opaque OTYPER register + pub struct OTYPER { + _0: (), + } + + impl OTYPER { + pub(crate) fn otyper(&mut self) -> &$gpioy::OTYPER { + unsafe { &(*$GPIOX::ptr()).otyper } + } + } + + /// Opaque PUPDR register + pub struct PUPDR { + _0: (), + } + + impl PUPDR { + pub(crate) fn pupdr(&mut self) -> &$gpioy::PUPDR { + unsafe { &(*$GPIOX::ptr()).pupdr } + } + } + + + /// Partially erased pin + pub struct $PXx { + i: u8, + _mode: PhantomData, + } + + impl $PXx { + /// The port this pin is part of. + pub const PORT: Port = Port::$PXx; + + /// Returns the port this pin is part of. + pub fn port(&self) -> Port { + Port::$PXx + } + + /// Returns this pin's number inside its port. + pub fn pin_number(&self) -> u8 { + self.i + } + } + + impl OutputPin for $PXx> { + type Error = void::Void; + + fn set_high(&mut self) -> Result<(), Self::Error> { + // NOTE(unsafe) atomic write to a stateless register + unsafe { (*$GPIOX::ptr()).bsrr.write(|w| w.bits(1 << self.i)) }; + Ok(()) + } + + fn set_low(&mut self) -> Result<(), Self::Error> { + // NOTE(unsafe) atomic write to a stateless register + unsafe { (*$GPIOX::ptr()).bsrr.write(|w| w.bits(1 << (self.i + 16))) }; + Ok(()) + } + } + + impl StatefulOutputPin for $PXx> { + fn is_set_high(&self) -> Result { + let is_high = self.is_set_low()?; + Ok(is_high) + } + + fn is_set_low(&self) -> Result { + // NOTE(unsafe) atomic read with no side effects + let is_low = unsafe { (*$GPIOX::ptr()).odr.read().bits() & (1 << self.i) == 0 }; + Ok(is_low) + } + } + + impl toggleable::Default for $PXx> {} + + impl InputPin for $PXx> { + type Error = void::Void; + + fn is_high(&self) -> Result { + let is_high = !self.is_low()?; + Ok(is_high) + } + + fn is_low(&self) -> Result { + // NOTE(unsafe) atomic read with no side effects + let is_low = unsafe { (*$GPIOX::ptr()).idr.read().bits() & (1 << self.i) == 0 }; + Ok(is_low) + } + } + + impl InputPin for $PXx> { + type Error = void::Void; + + fn is_high(&self) -> Result { + let is_high = !self.is_low()?; + Ok(is_high) + } + + fn is_low(&self) -> Result { + // NOTE(unsafe) atomic read with no side effects + let is_low = unsafe { (*$GPIOX::ptr()).idr.read().bits() & (1 << self.i) == 0 }; + Ok(is_low) + } + } + + $( + /// Pin + pub struct $PXi { + _mode: PhantomData, + } + + impl $PXi { + /// The port this pin is part of. + pub const PORT: Port = Port::$PXx; + + /// The pin's number inside its port. + pub const PIN_NUMBER: u8 = $i; + + /// Returns the port this pin is part of. + pub fn port(&self) -> Port { + Port::$PXx + } + + /// Returns this pin's number inside its port. + pub fn pin_number(&self) -> u8 { + $i + } + } + + impl $PXi { + /// Puts `self` into mode `M`. + /// + /// This violates the type state constraints from `MODE`, so callers must + /// ensure they use this properly. + fn mode(&mut self) { + let offset = 2 * $i; + unsafe { + &(*$GPIOX::ptr()).pupdr.modify(|r, w| { + w.bits((r.bits() & !(0b11 << offset)) | (u32::from(M::PUPDR) << offset)) + }); + + if let Some(otyper) = M::OTYPER { + &(*$GPIOX::ptr()).otyper.modify(|r, w| { + w.bits(r.bits() & !(0b1 << $i) | (u32::from(otyper) << $i)) + }); + } + + &(*$GPIOX::ptr()).moder.modify(|r, w| { + w.bits((r.bits() & !(0b11 << offset)) | (u32::from(M::MODER) << offset)) + }); + } + } + + fn with_mode( + &mut self, + f: F + ) -> R + where + M: PinMode, + F: FnOnce(&mut $PXi) -> R, + { + struct ResetMode<'a, ORIG: PinMode> { + pin: &'a mut $PXi, + } + + impl<'a, ORIG: PinMode> Drop for ResetMode<'a, ORIG> { + fn drop(&mut self) { + self.pin.mode::(); + } + } + + self.mode::(); + + // This will reset the pin back to the original mode when dropped. + // (so either when `with_mode` returns or when `f` unwinds) + let _resetti = ResetMode { pin: self }; + + let mut witness = $PXi { + _mode: PhantomData + }; + + f(&mut witness) + } + + /// Configures the pin to operate as a floating input pin. + pub fn into_floating_input( + mut self, + ) -> $PXi> { + self.mode::>(); + $PXi { + _mode: PhantomData + } + } + + /// Temporarily configures this pin as a floating input. + /// + /// The closure `f` is called with the reconfigured pin. After it returns, + /// the pin will be configured back. + pub fn with_floating_input( + &mut self, + f: impl FnOnce(&mut $PXi>) -> R, + ) -> R { + self.with_mode(f) + } + + /// Configures the pin to operate as a pulled-down input pin. + pub fn into_pull_down_input( + mut self, + ) -> $PXi> { + self.mode::>(); + $PXi { + _mode: PhantomData + } + } + + /// Temporarily configures this pin as a pulled-down input. + /// + /// The closure `f` is called with the reconfigured pin. After it returns, + /// the pin will be configured back. + pub fn with_pull_down_input( + &mut self, + f: impl FnOnce(&mut $PXi>) -> R, + ) -> R { + self.with_mode(f) + } + + /// Configures the pin to operate as a pulled-up input pin. + pub fn into_pull_up_input( + mut self, + ) -> $PXi> { + self.mode::>(); + $PXi { + _mode: PhantomData + } + } + + /// Temporarily configures this pin as a pulled-up input. + /// + /// The closure `f` is called with the reconfigured pin. After it returns, + /// the pin will be configured back. + pub fn with_pull_up_input( + &mut self, + f: impl FnOnce(&mut $PXi>) -> R, + ) -> R { + self.with_mode(f) + } + + /// Configures the pin to operate as an analog pin. + pub fn into_analog( + mut self, + ) -> $PXi { + self.mode::(); + $PXi { + _mode: PhantomData + } + } + + /// Temporarily configures this pin as an analog pin. + /// + /// The closure `f` is called with the reconfigured pin. After it returns, + /// the pin will be configured back. + pub fn with_analog( + &mut self, + f: impl FnOnce(&mut $PXi) -> R, + ) -> R { + self.with_mode(f) + } + + /// Configures the pin to operate as an open drain output pin. + pub fn into_open_drain_output( + mut self, + ) -> $PXi> { + self.mode::>(); + $PXi { + _mode: PhantomData + } + } + + /// Temporarily configures this pin as an open drain output. + /// + /// The closure `f` is called with the reconfigured pin. After it returns, + /// the pin will be configured back. + pub fn with_open_drain_output( + &mut self, + f: impl FnOnce(&mut $PXi>) -> R, + ) -> R { + self.with_mode(f) + } /// Configures the pin to operate as an open drain output pin. - pub fn into_open_drain_output( + pub fn into_alt_open_drain_output( mut self, - ) -> $PXi> { - self.mode::>(); + mode: AltMode, + ) -> $PXi> { + self.set_alt_mode(mode); + self.mode::>(); $PXi { _mode: PhantomData } } - /// Temporarily configures this pin as an open drain output. - /// - /// The closure `f` is called with the reconfigured pin. After it returns, - /// the pin will be configured back. - pub fn with_open_drain_output( - &mut self, - f: impl FnOnce(&mut $PXi>) -> R, - ) -> R { - self.with_mode(f) - } - - /// Configures the pin to operate as an push-pull output pin. - pub fn into_push_pull_output( - mut self, - ) -> $PXi> { - self.mode::>(); - $PXi { - _mode: PhantomData - } - } - - /// Temporarily configures this pin as a push-pull output. - /// - /// The closure `f` is called with the reconfigured pin. After it returns, - /// the pin will be configured back. - pub fn with_push_pull_output( - &mut self, - f: impl FnOnce(&mut $PXi>) -> R, - ) -> R { - self.with_mode(f) - } - - /// Set pin speed. - pub fn set_speed(self, speed: Speed) -> Self { - let offset = 2 * $i; - unsafe { - &(*$GPIOX::ptr()).ospeedr.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | ((speed as u32) << offset)) - }) - }; - self - } - - #[allow(dead_code)] - pub(crate) fn set_alt_mode(&self, mode: AltMode) { - let mode = mode as u32; - let offset = 2 * $i; - let offset2 = 4 * $i; - unsafe { - if offset2 < 32 { - &(*$GPIOX::ptr()).afrl.modify(|r, w| { - w.bits((r.bits() & !(0b1111 << offset2)) | (mode << offset2)) - }); - } else { - let offset2 = offset2 - 32; - &(*$GPIOX::ptr()).afrh.modify(|r, w| { - w.bits((r.bits() & !(0b1111 << offset2)) | (mode << offset2)) - }); - } - &(*$GPIOX::ptr()).moder.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b10 << offset)) - }); - } - } - } - - impl $PXi> { - /// Erases the pin number from the type - /// - /// This is useful when you want to collect the pins into an array where you - /// need all the elements to have the same type - pub fn downgrade(self) -> $PXx> { - $PXx { - i: $i, - _mode: self._mode, - } - } - } - - impl OutputPin for $PXi> { - type Error = void::Void; - - fn set_high(&mut self) -> Result<(), Self::Error> { - // NOTE(unsafe) atomic write to a stateless register - unsafe { (*$GPIOX::ptr()).bsrr.write(|w| w.bits(1 << $i)) }; - Ok(()) - } - - fn set_low(&mut self) -> Result<(), Self::Error> { - // NOTE(unsafe) atomic write to a stateless register - unsafe { (*$GPIOX::ptr()).bsrr.write(|w| w.bits(1 << ($i + 16))) }; - Ok(()) - } - } - - impl StatefulOutputPin for $PXi> { - - fn is_set_high(&self) -> Result { - let is_set_high = !self.is_set_low()?; - Ok(is_set_high) - } - - fn is_set_low(&self) -> Result { - // NOTE(unsafe) atomic read with no side effects - let is_set_low = unsafe { (*$GPIOX::ptr()).odr.read().bits() & (1 << $i) == 0 }; - Ok(is_set_low) - } - } - - impl toggleable::Default for $PXi> {} - - impl InputPin for $PXi> { - type Error = void::Void; - - fn is_high(&self) -> Result { - let is_high = !self.is_low()?; - Ok(is_high) - } - - fn is_low(&self) -> Result { - // NOTE(unsafe) atomic read with no side effects - let is_low = unsafe { (*$GPIOX::ptr()).idr.read().bits() & (1 << $i) == 0 }; - Ok(is_low) - } - } - - impl $PXi> { - /// Erases the pin number from the type - /// - /// This is useful when you want to collect the pins into an array where you - /// need all the elements to have the same type - pub fn downgrade(self) -> $PXx> { - $PXx { - i: $i, - _mode: self._mode, - } - } - } - - impl InputPin for $PXi> { - type Error = void::Void; - - fn is_high(&self) -> Result { - let is_high = !self.is_low()?; - Ok(is_high) - } - - fn is_low(&self) -> Result { - // NOTE(unsafe) atomic read with no side effects - let is_low = unsafe { (*$GPIOX::ptr()).idr.read().bits() & (1 << $i) == 0 }; - Ok(is_low) - } - } - )+ - } - } + /// Configures the pin to operate as an push-pull output pin. + pub fn into_push_pull_output( + mut self, + ) -> $PXi> { + self.mode::>(); + $PXi { + _mode: PhantomData + } + } + + /// Temporarily configures this pin as a push-pull output. + /// + /// The closure `f` is called with the reconfigured pin. After it returns, + /// the pin will be configured back. + pub fn with_push_pull_output( + &mut self, + f: impl FnOnce(&mut $PXi>) -> R, + ) -> R { + self.with_mode(f) + } + + /// Set pin speed. + pub fn set_speed(self, speed: Speed) -> Self { + let offset = 2 * $i; + unsafe { + &(*$GPIOX::ptr()).ospeedr.modify(|r, w| { + w.bits((r.bits() & !(0b11 << offset)) | ((speed as u32) << offset)) + }) + }; + self + } + + #[allow(dead_code)] + pub fn set_alt_mode(&self, mode: AltMode) { + let mode = mode as u32; + let offset = 2 * $i; + let offset2 = 4 * $i; + unsafe { + if offset2 < 32 { + &(*$GPIOX::ptr()).afrl.modify(|r, w| { + w.bits((r.bits() & !(0b1111 << offset2)) | (mode << offset2)) + }); + } else { + let offset2 = offset2 - 32; + &(*$GPIOX::ptr()).afrh.modify(|r, w| { + w.bits((r.bits() & !(0b1111 << offset2)) | (mode << offset2)) + }); + } + &(*$GPIOX::ptr()).moder.modify(|r, w| { + w.bits((r.bits() & !(0b11 << offset)) | (0b10 << offset)) + }); + } + } + } + + impl $PXi> { + /// Erases the pin number from the type + /// + /// This is useful when you want to collect the pins into an array where you + /// need all the elements to have the same type + pub fn downgrade(self) -> $PXx> { + $PXx { + i: $i, + _mode: self._mode, + } + } + } + + impl OutputPin for $PXi> { + type Error = void::Void; + + fn set_high(&mut self) -> Result<(), Self::Error> { + // NOTE(unsafe) atomic write to a stateless register + unsafe { (*$GPIOX::ptr()).bsrr.write(|w| w.bits(1 << $i)) }; + Ok(()) + } + + fn set_low(&mut self) -> Result<(), Self::Error> { + // NOTE(unsafe) atomic write to a stateless register + unsafe { (*$GPIOX::ptr()).bsrr.write(|w| w.bits(1 << ($i + 16))) }; + Ok(()) + } + } + + impl StatefulOutputPin for $PXi> { + + fn is_set_high(&self) -> Result { + let is_set_high = !self.is_set_low()?; + Ok(is_set_high) + } + + fn is_set_low(&self) -> Result { + // NOTE(unsafe) atomic read with no side effects + let is_set_low = unsafe { (*$GPIOX::ptr()).odr.read().bits() & (1 << $i) == 0 }; + Ok(is_set_low) + } + } + + impl toggleable::Default for $PXi> {} + + impl InputPin for $PXi> { + type Error = void::Void; + + fn is_high(&self) -> Result { + let is_high = !self.is_low()?; + Ok(is_high) + } + + fn is_low(&self) -> Result { + // NOTE(unsafe) atomic read with no side effects + let is_low = unsafe { (*$GPIOX::ptr()).idr.read().bits() & (1 << $i) == 0 }; + Ok(is_low) + } + } + + impl $PXi> { + /// Erases the pin number from the type + /// + /// This is useful when you want to collect the pins into an array where you + /// need all the elements to have the same type + pub fn downgrade(self) -> $PXx> { + $PXx { + i: $i, + _mode: self._mode, + } + } + } + + impl InputPin for $PXi> { + type Error = void::Void; + + fn is_high(&self) -> Result { + let is_high = !self.is_low()?; + Ok(is_high) + } + + fn is_low(&self) -> Result { + // NOTE(unsafe) atomic read with no side effects + let is_low = unsafe { (*$GPIOX::ptr()).idr.read().bits() & (1 << $i) == 0 }; + Ok(is_low) + } + } + )+ + } + } } -gpio!(GPIOA, gpioa, iopaen, PA, [ - PA0: (pa0, 0, Analog), - PA1: (pa1, 1, Analog), - PA2: (pa2, 2, Analog), - PA3: (pa3, 3, Analog), - PA4: (pa4, 4, Analog), - PA5: (pa5, 5, Analog), - PA6: (pa6, 6, Analog), - PA7: (pa7, 7, Analog), - PA8: (pa8, 8, Analog), - PA9: (pa9, 9, Analog), - PA10: (pa10, 10, Analog), - PA11: (pa11, 11, Analog), - PA12: (pa12, 12, Analog), - PA13: (pa13, 13, Analog), - PA14: (pa14, 14, Analog), - PA15: (pa15, 15, Analog), +gpio!(GPIOA, gpioa, gpioa, iopaen, ioparst, PA, [ + PA0: (pa0, 0, Analog, AFRL), + PA1: (pa1, 1, Analog, AFRL), + PA2: (pa2, 2, Analog, AFRL), + PA3: (pa3, 3, Analog, AFRL), + PA4: (pa4, 4, Analog, AFRL), + PA5: (pa5, 5, Analog, AFRL), + PA6: (pa6, 6, Analog, AFRL), + PA7: (pa7, 7, Analog, AFRL), + PA8: (pa8, 8, Analog, AFRH), + PA9: (pa9, 9, Analog, AFRH), + PA10: (pa10, 10, Analog, AFRH), + PA11: (pa11, 11, Analog, AFRH), + PA12: (pa12, 12, Analog, AFRH), + PA13: (pa13, 13, Analog, AFRH), + PA14: (pa14, 14, Analog, AFRH), + PA15: (pa15, 15, Analog, AFRH), ]); -gpio!(GPIOB, gpiob, iopben, PB, [ - PB0: (pb0, 0, Analog), - PB1: (pb1, 1, Analog), - PB2: (pb2, 2, Analog), - PB3: (pb3, 3, Analog), - PB4: (pb4, 4, Analog), - PB5: (pb5, 5, Analog), - PB6: (pb6, 6, Analog), - PB7: (pb7, 7, Analog), - PB8: (pb8, 8, Analog), - PB9: (pb9, 9, Analog), - PB10: (pb10, 10, Analog), - PB11: (pb11, 11, Analog), - PB12: (pb12, 12, Analog), - PB13: (pb13, 13, Analog), - PB14: (pb14, 14, Analog), - PB15: (pb15, 15, Analog), +gpio!(GPIOB, gpiob, gpiob, iopben, iopbrst, PB, [ + PB0: (pb0, 0, Analog, AFRL), + PB1: (pb1, 1, Analog, AFRL), + PB2: (pb2, 2, Analog, AFRL), + PB3: (pb3, 3, Analog, AFRL), + PB4: (pb4, 4, Analog, AFRL), + PB5: (pb5, 5, Analog, AFRL), + PB6: (pb6, 6, Analog, AFRL), + PB7: (pb7, 7, Analog, AFRL), + PB8: (pb8, 8, Analog, AFRH), + PB9: (pb9, 9, Analog, AFRH), + PB10: (pb10, 10, Analog, AFRH), + PB11: (pb11, 11, Analog, AFRH), + PB12: (pb12, 12, Analog, AFRH), + PB13: (pb13, 13, Analog, AFRH), + PB14: (pb14, 14, Analog, AFRH), + PB15: (pb15, 15, Analog, AFRH), ]); -gpio!(GPIOC, gpioc, iopcen, PC, [ - PC0: (pc0, 0, Analog), - PC1: (pc1, 1, Analog), - PC2: (pc2, 2, Analog), - PC3: (pc3, 3, Analog), - PC4: (pc4, 4, Analog), - PC5: (pc5, 5, Analog), - PC6: (pc6, 6, Analog), - PC7: (pc7, 7, Analog), - PC8: (pc8, 8, Analog), - PC9: (pc9, 9, Analog), - PC10: (pc10, 10, Analog), - PC11: (pc11, 11, Analog), - PC12: (pc12, 12, Analog), - PC13: (pc13, 13, Analog), - PC14: (pc14, 14, Analog), - PC15: (pc15, 15, Analog), +// gpio[c,d,e,h] module are derived from gpiob +gpio!(GPIOC, gpioc, gpiob, iopcen, iopcrst, PC, [ + PC0: (pc0, 0, Analog, AFRL), + PC1: (pc1, 1, Analog, AFRL), + PC2: (pc2, 2, Analog, AFRL), + PC3: (pc3, 3, Analog, AFRL), + PC4: (pc4, 4, Analog, AFRL), + PC5: (pc5, 5, Analog, AFRL), + PC6: (pc6, 6, Analog, AFRL), + PC7: (pc7, 7, Analog, AFRL), + PC8: (pc8, 8, Analog, AFRH), + PC9: (pc9, 9, Analog, AFRH), + PC10: (pc10, 10, Analog, AFRH), + PC11: (pc11, 11, Analog, AFRH), + PC12: (pc12, 12, Analog, AFRH), + PC13: (pc13, 13, Analog, AFRH), + PC14: (pc14, 14, Analog, AFRH), + PC15: (pc15, 15, Analog, AFRH), ]); -gpio!(GPIOD, gpiod, iopden, PD, [ - PD0: (pd0, 0, Analog), - PD1: (pd1, 1, Analog), - PD2: (pd2, 2, Analog), - PD3: (pd3, 3, Analog), - PD4: (pd4, 4, Analog), - PD5: (pd5, 5, Analog), - PD6: (pd6, 6, Analog), - PD7: (pd7, 7, Analog), - PD8: (pd8, 8, Analog), - PD9: (pd9, 9, Analog), - PD10: (pd10, 10, Analog), - PD11: (pd11, 11, Analog), - PD12: (pd12, 12, Analog), - PD13: (pd13, 13, Analog), - PD14: (pd14, 14, Analog), - PD15: (pd15, 15, Analog), +gpio!(GPIOD, gpiod, gpiob, iopden, iopdrst, PD, [ + PD0: (pd0, 0, Analog, AFRL), + PD1: (pd1, 1, Analog, AFRL), + PD2: (pd2, 2, Analog, AFRL), + PD3: (pd3, 3, Analog, AFRL), + PD4: (pd4, 4, Analog, AFRL), + PD5: (pd5, 5, Analog, AFRL), + PD6: (pd6, 6, Analog, AFRL), + PD7: (pd7, 7, Analog, AFRL), + PD8: (pd8, 8, Analog, AFRH), + PD9: (pd9, 9, Analog, AFRH), + PD10: (pd10, 10, Analog, AFRH), + PD11: (pd11, 11, Analog, AFRH), + PD12: (pd12, 12, Analog, AFRH), + PD13: (pd13, 13, Analog, AFRH), + PD14: (pd14, 14, Analog, AFRH), + PD15: (pd15, 15, Analog, AFRH), ]); -gpio!(GPIOE, gpioe, iopeen, PE, [ - PE0: (pe0, 0, Analog), - PE1: (pe1, 1, Analog), - PE2: (pe2, 2, Analog), - PE3: (pe3, 3, Analog), - PE4: (pe4, 4, Analog), - PE5: (pe5, 5, Analog), - PE6: (pe6, 6, Analog), - PE7: (pe7, 7, Analog), - PE8: (pe8, 8, Analog), - PE9: (pe9, 9, Analog), - PE10: (pe10, 10, Analog), - PE11: (pe11, 11, Analog), - PE12: (pe12, 12, Analog), - PE13: (pe13, 13, Analog), - PE14: (pe14, 14, Analog), - PE15: (pe15, 15, Analog), +gpio!(GPIOE, gpioe, gpiob, iopeen, ioperst, PE, [ + PE0: (pe0, 0, Analog, AFRL), + PE1: (pe1, 1, Analog, AFRL), + PE2: (pe2, 2, Analog, AFRL), + PE3: (pe3, 3, Analog, AFRL), + PE4: (pe4, 4, Analog, AFRL), + PE5: (pe5, 5, Analog, AFRL), + PE6: (pe6, 6, Analog, AFRL), + PE7: (pe7, 7, Analog, AFRL), + PE8: (pe8, 8, Analog, AFRH), + PE9: (pe9, 9, Analog, AFRH), + PE10: (pe10, 10, Analog, AFRH), + PE11: (pe11, 11, Analog, AFRH), + PE12: (pe12, 12, Analog, AFRH), + PE13: (pe13, 13, Analog, AFRH), + PE14: (pe14, 14, Analog, AFRH), + PE15: (pe15, 15, Analog, AFRH), ]); -gpio!(GPIOH, gpioh, iophen, PH, [ - PH0: (ph0, 0, Analog), - PH1: (ph1, 1, Analog), - PH9: (ph9, 9, Analog), - PH10: (ph10, 10, Analog), +gpio!(GPIOH, gpioh, gpiob, iophen, iophrst, PH, [ + PH0: (ph0, 0, Analog, AFRL), + PH1: (ph1, 1, Analog, AFRL), + PH9: (ph9, 9, Analog, AFRH), + PH10: (ph10, 10, Analog, AFRH), ]); diff --git a/src/i2c.rs b/src/i2c.rs index 4cff2388..09367473 100755 --- a/src/i2c.rs +++ b/src/i2c.rs @@ -2,13 +2,16 @@ use core::ops::Deref; +#[cfg(feature = "stm32l0x0")] +use core::{marker::PhantomData}; + #[cfg(feature = "stm32l0x2")] use core::{marker::PhantomData, ops::DerefMut, pin::Pin}; #[cfg(feature = "stm32l0x2")] use as_slice::{AsMutSlice, AsSlice}; -#[cfg(feature = "stm32l0x2")] +#[cfg(any(feature = "stm32l0x0", feature = "stm32l0x2"))] use crate::dma::{self, Buffer}; use crate::pac::i2c1::{ cr2::{AUTOEND_A, RD_WRN_A}, @@ -22,12 +25,22 @@ use cast::u8; use crate::hal::blocking::i2c::{Read, Write, WriteRead}; // I/O Imports -use crate::gpio::{AltMode, OpenDrain, Output}; -#[cfg(feature = "io-STM32L051")] +use crate::gpio::{AltMode, AltOpenDrain, OpenDrain, Output}; +#[cfg(feature = "stm32l0x0")] +use crate::{ + gpio::gpioa::{PA9, PA10}, + gpio::gpiob::{PB10, PB13, PB7, PB9}, + pac::I2C1, +}; + +#[cfg(all(feature = "io-STM32L051", not(feature = "stm32l0x0")))] use crate::{ gpio::gpiob::{PB10, PB11, PB13, PB14, PB6, PB7, PB8, PB9}, - pac::{I2C1, I2C2}, + pac::I2C1, }; +#[cfg(all(feature = "io-STM32L051", not(feature = "stm32l0x0")))] +use create::pac::I2C2; + #[cfg(feature = "io-STM32L021")] use crate::{ gpio::{ @@ -538,58 +551,65 @@ macro_rules! i2c { }; } -#[cfg(feature = "io-STM32L021")] +#[cfg(feature= "stm32l0x0")] i2c!( I2C1, i2c1en, i2c1rst, sda: [ - (PA10>, AltMode::AF1), - (PA13>, AltMode::AF3), + (PA10>, AltMode::AF6), (PB7>, AltMode::AF1), - ], + (PB9>, AltMode::AF4), + ], scl: [ - (PA4>, AltMode::AF3), - (PA9>, AltMode::AF1), - (PB6>, AltMode::AF1), - (PB8>, AltMode::AF4), - ], + (PA9>, AltMode::AF6), + (PB10>, AltMode::AF6), + (PB13>, AltMode::AF5), + ], ); -#[cfg(feature = "io-STM32L031")] + +#[cfg(feature = "io-STM32L021")] i2c!( I2C1, i2c1en, i2c1rst, sda: [ (PA10>, AltMode::AF1), + (PA13>, AltMode::AF3), (PB7>, AltMode::AF1), - (PB9>, AltMode::AF4), ], scl: [ + (PA4>, AltMode::AF3), (PA9>, AltMode::AF1), (PB6>, AltMode::AF1), (PB8>, AltMode::AF4), ], ); -#[cfg(feature = "io-STM32L051")] +#[cfg(feature = "io-STM32L031")] i2c!( I2C1, i2c1en, i2c1rst, sda: [ + (PA10>, AltMode::AF1), (PB7>, AltMode::AF1), (PB9>, AltMode::AF4), ], scl: [ + (PA9>, AltMode::AF1), (PB6>, AltMode::AF1), (PB8>, AltMode::AF4), ], ); -#[cfg(feature = "io-STM32L051")] +#[cfg(all(feature = "io-STM32L051", not(feature = "stm32l0x0")))] i2c!( I2C2, i2c2en, i2c2rst, sda: [ + (PB7>, AltMode::AF1), + (PB9>, AltMode::AF4), (PB11>, AltMode::AF6), (PB14>, AltMode::AF5), ], scl: [ + (PB6>, AltMode::AF1), + (PB8>, AltMode::AF4), (PB10>, AltMode::AF6), (PB13>, AltMode::AF5), ], @@ -641,24 +661,24 @@ i2c!( /// /// This is an implementation detail. The user doesn't have to deal with this /// directly. -#[cfg(feature = "stm32l0x2")] +#[cfg(any(feature = "stm32l0x0", feature = "stm32l0x2"))] pub struct Tx(PhantomData); /// Token used for DMA transfers /// /// This is an implementation detail. The user doesn't have to deal with this /// directly. -#[cfg(feature = "stm32l0x2")] +#[cfg(any(feature = "stm32l0x0", feature = "stm32l0x2"))] pub struct Rx(PhantomData); /// I2C-specific wrapper around [`dma::Transfer`] -#[cfg(feature = "stm32l0x2")] +#[cfg(any(feature = "stm32l0x0", feature = "stm32l0x2"))] pub struct Transfer { target: Target, inner: dma::Transfer, } -#[cfg(feature = "stm32l0x2")] +#[cfg(any(feature = "stm32l0x0", feature = "stm32l0x2"))] impl Transfer where Token: dma::Target, @@ -684,7 +704,7 @@ where } } -#[cfg(feature = "stm32l0x2")] +#[cfg(any(feature = "stm32l0x0", feature = "stm32l0x2"))] impl Transfer where Channel: dma::Channel, diff --git a/src/lib.rs b/src/lib.rs index 9480c05c..ea7785ed 100755 --- a/src/lib.rs +++ b/src/lib.rs @@ -1,13 +1,15 @@ #![cfg_attr(not(test), no_std)] #![allow(non_camel_case_types)] -#[cfg(not(any(feature = "stm32l0x1", feature = "stm32l0x2", feature = "stm32l0x3")))] +#[cfg(not(any(feature = "stm32l0x0", feature = "stm32l0x1", feature = "stm32l0x2", feature = "stm32l0x3")))] compile_error!( - "This crate requires one of the following features enabled: stm32l0x1, stm32l0x2, stm32l0x3" + "This crate requires one of the following features enabled: stm32l0x0, stm32l0x1, stm32l0x2, stm32l0x3" ); use embedded_hal as hal; +#[cfg(feature = "stm32l0x0")] +pub use stm32l0::stm32l0x0 as pac; #[cfg(feature = "stm32l0x1")] pub use stm32l0::stm32l0x1 as pac; #[cfg(feature = "stm32l0x2")] @@ -16,6 +18,7 @@ pub use stm32l0::stm32l0x2 as pac; pub use stm32l0::stm32l0x3 as pac; pub mod adc; +#[cfg(not(feature = "stm32l0x0"))] pub mod aes; pub mod calibration; pub mod delay; diff --git a/src/prelude.rs b/src/prelude.rs index ca5bcdcf..f96135c8 100755 --- a/src/prelude.rs +++ b/src/prelude.rs @@ -27,8 +27,11 @@ pub use crate::{ ))] pub use crate::i2c::I2cExt as _; -#[cfg(any(feature = "io-STM32L051", feature = "io-STM32L071",))] +#[cfg(all(not(feature = "stm32l0x0"), any(feature = "io-STM32L051", feature = "io-STM32L071")))] pub use crate::serial::{Serial1Ext as _, Serial1LpExt as _}; +#[cfg(feature = "stm32l0x0")] +pub use crate::serial::{Serial1LpExt as _}; + #[cfg(any( feature = "io-STM32L021", feature = "io-STM32L031", diff --git a/src/pwm.rs b/src/pwm.rs index 0b38febb..791960a9 100755 --- a/src/pwm.rs +++ b/src/pwm.rs @@ -6,7 +6,10 @@ use cortex_m::interrupt; use crate::gpio::gpioa::{PA0, PA1, PA2, PA3}; use crate::gpio::{AltMode, PinMode}; use crate::hal; -use crate::pac::{tim2, TIM2, TIM3}; + +use crate::pac::{tim2, TIM2}; +#[cfg(not(feature = "stm32l0x0"))] +use crate::pac::TIM3; use crate::rcc::Rcc; use crate::time::Hertz; use cast::{u16, u32}; @@ -132,6 +135,10 @@ macro_rules! impl_instance { impl_instance!( TIM2, apb1enr, apb1rstr, tim2en, tim2rst, apb1_clk; +); + +#[cfg(not(feature = "stm32l0x0"))] +impl_instance!( TIM3, apb1enr, apb1rstr, tim3en, tim3rst, apb1_clk; ); diff --git a/src/rcc.rs b/src/rcc.rs index 287af4db..e29f9325 100755 --- a/src/rcc.rs +++ b/src/rcc.rs @@ -1,6 +1,6 @@ use crate::mco; use crate::pac::rcc::cfgr::{MCOPRE_A, MCOSEL_A}; -use crate::pac::RCC; +use crate::pac::{rcc, RCC}; use crate::pwr::PWR; use crate::time::{Hertz, U32Ext}; @@ -102,10 +102,10 @@ pub const HSI_FREQ: u32 = 16_000_000; /// Clocks configutation pub struct Config { - mux: ClockSrc, - ahb_pre: AHBPrescaler, - apb1_pre: APBPrescaler, - apb2_pre: APBPrescaler, + pub mux: ClockSrc, + pub ahb_pre: AHBPrescaler, + pub apb1_pre: APBPrescaler, + pub apb2_pre: APBPrescaler, } impl Default for Config { @@ -192,7 +192,37 @@ impl Config { /// RCC peripheral pub struct Rcc { pub clocks: Clocks, - pub(crate) rb: RCC, + pub rb: RCC, + // GPIO clock enable register + pub iopenr: IOPENR, + // GPIO reset register + pub ioprstr: IOPRSTR, +} + + +// GPIO clock enable register +pub struct IOPENR { + _0: (), +} + +impl IOPENR { + pub(crate) fn enr(&mut self) -> &rcc::IOPENR { + // NOTE(unsafe) this proxy grants exclusive access to this register + unsafe { &(*RCC::ptr()).iopenr } + } +} + + +// GPIO reset register +pub struct IOPRSTR { + _0: (), +} + +impl IOPRSTR { + pub(crate) fn rstr(&mut self) -> &rcc::IOPRSTR { + // NOTE(unsafe) this proxy grants exclusive access to this register + unsafe { &(*RCC::ptr()).ioprstr } + } } impl Rcc { @@ -401,7 +431,12 @@ impl RccExt for RCC { apb2_tim_clk: apb2_tim_freq.hz(), }; - Rcc { rb: self, clocks } + Rcc { + rb: self, + clocks: clocks, + iopenr: IOPENR { _0: () }, + ioprstr: IOPRSTR { _0: () }, + } } } diff --git a/src/serial.rs b/src/serial.rs index 31965052..6f346204 100755 --- a/src/serial.rs +++ b/src/serial.rs @@ -7,22 +7,26 @@ use nb::block; use crate::gpio::{AltMode, PinMode}; use crate::hal; use crate::hal::prelude::*; -pub use crate::pac::{LPUART1, USART1, USART2, USART4, USART5}; + +pub use crate::pac::{LPUART1, USART2}; +#[cfg(not(feature = "stm32l0x0"))] +use crate::pac::{USART1, USART4, USART5}; + use crate::rcc::{Rcc, LSE}; -#[cfg(any(feature = "stm32l0x2", feature = "stm32l0x3"))] +#[cfg(any(feature = "stm32l0x0", feature = "stm32l0x2", feature = "stm32l0x3"))] use core::{ ops::{Deref, DerefMut}, pin::Pin, }; -#[cfg(any(feature = "stm32l0x2", feature = "stm32l0x3"))] +#[cfg(any(feature = "stm32l0x0", feature = "stm32l0x2", feature = "stm32l0x3"))] use as_slice::{AsMutSlice, AsSlice}; -#[cfg(any(feature = "stm32l0x2", feature = "stm32l0x3"))] +#[cfg(any(feature = "stm32l0x0", feature = "stm32l0x2", feature = "stm32l0x3"))] pub use crate::dma; -#[cfg(any(feature = "stm32l0x2", feature = "stm32l0x3"))] +#[cfg(any(feature = "stm32l0x0", feature = "stm32l0x2", feature = "stm32l0x3"))] use crate::dma::Buffer; #[cfg(any( @@ -218,7 +222,7 @@ impl_pins!( PC0, AF6, LPUART1, RxPin; ); -#[cfg(feature = "io-STM32L051")] +#[cfg(all(not(feature = "stm32l0x0"), feature = "io-STM32L051"))] impl_pins!( PA2, AF4, USART2, TxPin; PA3, AF4, USART2, RxPin; @@ -278,11 +282,26 @@ impl_pins!( PE11, AF6, USART5, RxPin; ); +#[cfg(feature = "stm32l0x0")] +impl_pins!( + PA2, AF4, USART2, TxPin; + PA3, AF4, USART2, RxPin; + PA14, AF4, USART2, TxPin; + PA15, AF4, USART2, RxPin; + PB10, AF4, LPUART1, TxPin; + PB11, AF4, LPUART1, RxPin; + PC4, AF2, LPUART1, TxPin; + PC5, AF2, LPUART1, RxPin; + PC10, AF0, LPUART1, TxPin; + PC11, AF0, LPUART1, RxPin; +); + + /// Serial abstraction pub struct Serial { - usart: USART, - rx: Rx, - tx: Tx, + pub usart: USART, + pub rx: Rx, + pub tx: Tx, } /// Serial receiver @@ -540,7 +559,7 @@ macro_rules! usart { } /// DMA operations. - #[cfg(any(feature = "stm32l0x2", feature = "stm32l0x3"))] + #[cfg(any(feature = "stm32l0x0", feature = "stm32l0x2", feature = "stm32l0x3"))] impl Rx<$USARTX> { pub fn read_all(self, dma: &mut dma::Handle, @@ -652,7 +671,7 @@ macro_rules! usart { } } - #[cfg(any(feature = "stm32l0x2", feature = "stm32l0x3"))] + #[cfg(any(feature = "stm32l0x0", feature = "stm32l0x2", feature = "stm32l0x3"))] impl Tx<$USARTX> { pub fn write_all(self, dma: &mut dma::Handle, @@ -722,7 +741,7 @@ usart! { } // USART1 is available on category 3/5 MCUs -#[cfg(any(feature = "io-STM32L051", feature = "io-STM32L071"))] +#[cfg(all(not(feature = "stm32l0x0"), any(feature = "io-STM32L051", feature = "io-STM32L071")))] usart! { USART1: (usart1, apb2enr, usart1en, apb1_clk, Serial1Ext), } diff --git a/src/spi.rs b/src/spi.rs index dae3fb74..9c6e956d 100755 --- a/src/spi.rs +++ b/src/spi.rs @@ -151,7 +151,7 @@ pins! { ] } -#[cfg(feature = "stm32l0x1")] +#[cfg(any(feature = "stm32l0x0", feature = "stm32l0x1"))] pins! { SPI1: SCK: [ diff --git a/src/timer.rs b/src/timer.rs index 782360a7..5864d821 100755 --- a/src/timer.rs +++ b/src/timer.rs @@ -1,6 +1,9 @@ //! Timers use crate::hal::timer::{CountDown, Periodic}; -use crate::pac::{tim2, tim21, tim22, tim6, TIM2, TIM21, TIM22, TIM3, TIM6}; + +use crate::pac::{tim2, tim21, tim22, TIM2, TIM21, TIM22}; +#[cfg(not(feature = "stm32l0x0"))] +use crate::pac::{tim6, TIM3, TIM6}; use crate::rcc::{Clocks, Rcc}; use crate::time::Hertz; use cast::{u16, u32}; @@ -211,15 +214,18 @@ macro_rules! timers { timers! { TIM2: (tim2, tim2en, tim2rst, apb1enr, apb1rstr, apb1_tim_clk, tim2::cr2::MMS_A), - TIM3: (tim3, tim3en, tim3rst, apb1enr, apb1rstr, apb1_tim_clk, - tim2::cr2::MMS_A), - TIM6: (tim6, tim6en, tim6rst, apb1enr, apb1rstr, apb1_tim_clk, - tim6::cr2::MMS_A), TIM21: (tim21, tim21en, tim21rst, apb2enr, apb2rstr, apb2_tim_clk, tim21::cr2::MMS_A), TIM22: (tim22, tim22en, tim22rst, apb2enr, apb2rstr, apb2_tim_clk, tim22::cr2::MMS_A), } +#[cfg(not(feature = "stm32l0x0"))] +timers! { + TIM3: (tim3, tim3en, tim3rst, apb1enr, apb1rstr, apb1_tim_clk, + tim2::cr2::MMS_A), + TIM6: (tim6, tim6en, tim6rst, apb1enr, apb1rstr, apb1_tim_clk, + tim6::cr2::MMS_A), +} pub trait GeneralPurposeTimer { type MasterMode; @@ -348,9 +354,13 @@ macro_rules! linked_timers { } } +#[cfg(not(feature = "stm32l0x0"))] linked_timers! { // Internal trigger connection: RM0377 table 76 (TIM2, TIM3): (tim2_tim3, apb1enr, apb1rstr, tim2en, tim3en, tim2rst, tim3rst, tim2::cr2::MMS_A, tim2::smcr::SMS_A, tim2::smcr::TS_A::ITR0), +} + +linked_timers! { // Internal trigger connection: RM0377 table 80 (TIM21, TIM22): (tim21_tim22, apb2enr, apb2rstr, tim21en, tim22en, tim21rst, tim22rst, tim21::cr2::MMS_A, tim22::smcr::SMS_A, tim22::smcr::TS_A::ITR0),