From e0a814dc454be43da7f0f76cb8f751bb4036fe79 Mon Sep 17 00:00:00 2001 From: Greg Green Date: Fri, 8 Nov 2024 12:30:49 -0800 Subject: [PATCH 01/11] Converting to embedded-hal 1.0 Added dma. Removed critical sections from gpio pins as this is really os dependent. Commented out modules: adc, i2c, pwm, timers, watchdog as they aren't yet converted. modules gpio, serial, spi are converted to embedded hal 1.0 --- Cargo.toml | 5 +- src/delay.rs | 125 ---------- src/dma.rs | 608 +++++++++++++++++++++++++++++++++++++++++++++++++ src/gpio.rs | 108 +++++---- src/lib.rs | 22 +- src/prelude.rs | 15 +- src/serial.rs | 109 +++++++-- src/spi.rs | 111 ++++----- 8 files changed, 818 insertions(+), 285 deletions(-) delete mode 100644 src/delay.rs create mode 100644 src/dma.rs diff --git a/Cargo.toml b/Cargo.toml index caf5347..668c9af 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -24,14 +24,17 @@ targets = ["thumbv6m-none-eabi"] bare-metal = { version = "1.0.0" } cast = "0.3.0" cortex-m = { version = "0.7.7", features = ["critical-section-single-core"] } -embedded-hal = { version = "0.2.7", features = ["unproven"] } +embedded-hal = "1.0.0" embedded-time = "0.12.1" +embedded-hal-nb = "1.0.0" +embedded-dma = "0.2.0" nb = "1.1.0" void = { version = "1.0.2", default-features = false } [dependencies.py32f0] version = "0.1.1" features = [] +path = "../py32-rs/py32f0" [dev-dependencies] cortex-m-rt = "0.7.3" diff --git a/src/delay.rs b/src/delay.rs deleted file mode 100644 index 090dd8e..0000000 --- a/src/delay.rs +++ /dev/null @@ -1,125 +0,0 @@ -//! API for delays with the systick timer -//! -//! Please be aware of potential overflows when using `delay_us`. -//! E.g. at 48MHz the maximum delay is 89 seconds. -//! -//! Consider using the timers api as a more flexible interface -//! -//! # Example -//! -//! ``` no_run -//! use py32f0xx_hal as hal; -//! -//! use crate::hal::pac; -//! use crate::hal::prelude::*; -//! use crate::hal::delay::Delay; -//! use cortex_m::peripheral::Peripherals; -//! -//! let mut p = pac::Peripherals::take().unwrap(); -//! let mut cp = cortex_m::Peripherals::take().unwrap(); -//! -//! let mut rcc = p.RCC.configure().freeze(&mut p.FLASH); -//! let mut delay = Delay::new(cp.SYST, &rcc); -//! loop { -//! delay.delay_ms(1_000_u16); -//! } -//! ``` - -use cast::{u16, u32}; -use cortex_m::peripheral::syst::SystClkSource; -use cortex_m::peripheral::SYST; - -use crate::rcc::Rcc; - -use embedded_hal::blocking::delay::{DelayMs, DelayUs}; - -/// System timer (SysTick) as a delay provider -#[derive(Clone)] -pub struct Delay { - scale: u32, -} - -const SYSTICK_RANGE: u32 = 0x0100_0000; - -impl Delay { - /// Configures the system timer (SysTick) as a delay provider - pub fn new(mut syst: SYST, rcc: &Rcc) -> Delay { - syst.set_clock_source(SystClkSource::Core); - - syst.set_reload(SYSTICK_RANGE - 1); - syst.clear_current(); - syst.enable_counter(); - - assert!(rcc.clocks.hclk().0 >= 1_000_000); - let scale = rcc.clocks.hclk().0 / 1_000_000; - - Delay { scale } - // As access to the count register is possible without a reference to the systick, we can - // just drop it - } -} - -impl DelayMs for Delay { - // At 48 MHz (the maximum frequency), calling delay_us with ms * 1_000 directly overflows at 0x15D86 (just over the max u16 value) - // So we implement a separate, higher level, delay loop - fn delay_ms(&mut self, mut ms: u32) { - const MAX_MS: u32 = 0x0000_FFFF; - while ms != 0 { - let current_ms = if ms <= MAX_MS { ms } else { MAX_MS }; - self.delay_us(current_ms * 1_000); - ms -= current_ms; - } - } -} - -impl DelayMs for Delay { - fn delay_ms(&mut self, ms: u16) { - // Call delay_us directly, so we don't have to use the additional - // delay loop the u32 variant uses - self.delay_us(u32(ms) * 1_000); - } -} - -impl DelayMs for Delay { - fn delay_ms(&mut self, ms: u8) { - self.delay_ms(u16(ms)); - } -} - -// At 48MHz (the maximum frequency), this overflows at approx. 2^32 / 48 = 89 seconds -impl DelayUs for Delay { - fn delay_us(&mut self, us: u32) { - // The SysTick Reload Value register supports values between 1 and 0x00FFFFFF. - // Here less than maximum is used so we have some play if there's a long running interrupt. - const MAX_TICKS: u32 = 0x007F_FFFF; - - let mut total_ticks = us * self.scale; - - while total_ticks != 0 { - let current_ticks = if total_ticks <= MAX_TICKS { - total_ticks - } else { - MAX_TICKS - }; - - let start_count = SYST::get_current(); - total_ticks -= current_ticks; - - // Use the wrapping substraction and the modulo to deal with the systick wrapping around - // from 0 to 0xFFFF - while (start_count.wrapping_sub(SYST::get_current()) % SYSTICK_RANGE) < current_ticks {} - } - } -} - -impl DelayUs for Delay { - fn delay_us(&mut self, us: u16) { - self.delay_us(u32(us)) - } -} - -impl DelayUs for Delay { - fn delay_us(&mut self, us: u8) { - self.delay_us(u32(us)) - } -} diff --git a/src/dma.rs b/src/dma.rs new file mode 100644 index 0000000..8bbc76f --- /dev/null +++ b/src/dma.rs @@ -0,0 +1,608 @@ +//! # Direct Memory Access +#![allow(dead_code)] + +use crate::pac; +use core::{ + convert::TryFrom, + marker::PhantomData, + mem, ptr, + sync::atomic::{self, compiler_fence, Ordering}, +}; +use embedded_dma::{ReadBuffer, WriteBuffer}; + +#[derive(Debug)] +#[non_exhaustive] +pub enum Error { + Overrun, +} + +#[derive(Clone, Copy, Debug, PartialEq, Eq)] +pub enum Event { + HalfTransfer, + TransferComplete, +} + +#[derive(Clone, Copy, Debug, PartialEq, Eq)] +pub enum Half { + First, + Second, +} + +#[derive(Clone, Copy, Debug, PartialEq, Eq)] +pub enum Priority { + Low, + Medium, + High, + VeryHigh, +} + +impl core::convert::From for u8 { + fn from(val: Priority) -> u8 { + match val { + Priority::Low => 0, + Priority::Medium => 1, + Priority::High => 2, + Priority::VeryHigh => 3, + } + } +} + +#[derive(Clone, Copy, Debug, PartialEq, Eq)] +pub enum TransferDir { + FromMemory, + FromPeripheral, +} + +impl core::convert::From for bool { + fn from(val: TransferDir) -> bool { + match val { + TransferDir::FromMemory => true, + TransferDir::FromPeripheral => false, + } + } +} + +#[derive(Clone, Copy, Debug, PartialEq, Eq)] +pub enum DataSize { + Bits8, + Bits16, + Bits32, +} + +impl core::convert::From for u8 { + fn from(val: DataSize) -> u8 { + match val { + DataSize::Bits8 => 0, + DataSize::Bits16 => 1, + DataSize::Bits32 => 2, + } + } +} + +pub struct CircBuffer +where + BUFFER: 'static, +{ + buffer: &'static mut [BUFFER; 2], + payload: PAYLOAD, + readable_half: Half, +} + +impl CircBuffer +where + &'static mut [BUFFER; 2]: WriteBuffer, + BUFFER: 'static, +{ + pub(crate) fn new(buf: &'static mut [BUFFER; 2], payload: PAYLOAD) -> Self { + CircBuffer { + buffer: buf, + payload, + readable_half: Half::Second, + } + } +} + +pub trait DmaExt { + type Channels; + + fn split(self) -> Self::Channels; + + fn ptr() -> *const pac::dma::RegisterBlock; +} + +pub trait TransferPayload { + fn start(&mut self); + fn stop(&mut self); +} + +pub struct Transfer +where + PAYLOAD: TransferPayload, +{ + _mode: PhantomData, + buffer: BUFFER, + payload: PAYLOAD, +} + +impl Transfer +where + PAYLOAD: TransferPayload, +{ + pub(crate) fn r(buffer: BUFFER, payload: PAYLOAD) -> Self { + Transfer { + _mode: PhantomData, + buffer, + payload, + } + } +} + +impl Transfer +where + PAYLOAD: TransferPayload, +{ + pub(crate) fn w(buffer: BUFFER, payload: PAYLOAD) -> Self { + Transfer { + _mode: PhantomData, + buffer, + payload, + } + } +} + +impl Drop for Transfer +where + PAYLOAD: TransferPayload, +{ + fn drop(&mut self) { + self.payload.stop(); + compiler_fence(Ordering::SeqCst); + } +} + +/// Read transfer +pub struct R; + +/// Write transfer +pub struct W; + +/// A singleton that represents a single DMAx channel (channel X in this case) +/// +/// This singleton has exclusive access to the registers of the DMAx channel X +#[non_exhaustive] +pub struct Ch(PhantomData); + +impl Ch { + /// Associated peripheral `address` + /// + /// `inc` indicates whether the address will be incremented after every byte transfer + pub fn set_peripheral_address(&mut self, address: u32, inc: bool) { + self.ch().par.write(|w| w.pa().bits(address)); + self.ch().cr.modify(|_, w| w.pinc().bit(inc)); + } + + /// `address` where from/to data will be read/write + /// + /// `inc` indicates whether the address will be incremented after every byte transfer + pub fn set_memory_address(&mut self, address: u32, inc: bool) { + self.ch().mar.write(|w| w.ma().bits(address)); + self.ch().cr.modify(|_, w| w.minc().bit(inc)); + } + + /// 'priority' sets the dma channel priority + pub fn set_priority(&mut self, priority: Priority) { + let prio_bits: u8 = priority.into(); + self.ch().cr.modify(|_, w| w.pl().bits(prio_bits)); + } + + /// Number of bytes to transfer + pub fn set_transfer_length(&mut self, len: usize) { + self.ch() + .ndtr + .write(|w| w.ndt().bits(u16::try_from(len).unwrap())); + } + + /// Starts the DMA transfer + pub fn start(&mut self) { + self.ch().cr.modify(|_, w| w.en().set_bit()); + } + + /// Stops the DMA transfer + pub fn stop(&mut self) { + self.ifcr().write(|w| unsafe { w.cgif::().clear() }); + self.ch().cr.modify(|_, w| w.en().clear_bit()); + } + + /// Returns `true` if there's a transfer in progress + pub fn in_progress(&self) -> bool { + unsafe { self.isr().tcif(C).bit_is_clear() } + } + + pub fn listen(&mut self, event: Event) { + match event { + Event::HalfTransfer => self.ch().cr.modify(|_, w| w.htie().set_bit()), + Event::TransferComplete => self.ch().cr.modify(|_, w| w.tcie().set_bit()), + } + } + + pub fn unlisten(&mut self, event: Event) { + match event { + Event::HalfTransfer => self.ch().cr.modify(|_, w| w.htie().clear_bit()), + Event::TransferComplete => self.ch().cr.modify(|_, w| w.tcie().clear_bit()), + } + } + + pub fn ch(&mut self) -> &pac::dma::CH { + unsafe { &(*DMA::ptr()).ch[C as usize] } + } + + pub fn isr(&self) -> pac::dma::isr::R { + // NOTE(unsafe) atomic read with no side effects + unsafe { (*DMA::ptr()).isr.read() } + } + + pub fn ifcr(&self) -> &pac::dma::IFCR { + unsafe { &(*DMA::ptr()).ifcr } + } + + pub fn get_ndtr(&self) -> u32 { + // NOTE(unsafe) atomic read with no side effects + unsafe { (*DMA::ptr()).ch[C as usize].ndtr.read().bits() } + } +} + +impl CircBuffer>> +where + RxDma>: TransferPayload, +{ + /// Peeks into the readable half of the buffer + pub fn peek(&mut self, f: F) -> Result + where + F: FnOnce(&B, Half) -> R, + { + let half_being_read = self.readable_half()?; + + let buf = match half_being_read { + Half::First => &self.buffer[0], + Half::Second => &self.buffer[1], + }; + + // XXX does this need a compiler barrier? + let ret = f(buf, half_being_read); + + let isr = self.payload.channel.isr(); + let first_half_is_done = unsafe { isr.htif(C).bit_is_set() }; + let second_half_is_done = unsafe { isr.tcif(C).bit_is_set() }; + + if (half_being_read == Half::First && second_half_is_done) + || (half_being_read == Half::Second && first_half_is_done) + { + Err(Error::Overrun) + } else { + Ok(ret) + } + } + + /// Returns the `Half` of the buffer that can be read + pub fn readable_half(&mut self) -> Result { + let isr = self.payload.channel.isr(); + let first_half_is_done = unsafe { isr.htif(C).bit_is_set() }; + let second_half_is_done = unsafe { isr.tcif(C).bit_is_set() }; + + if first_half_is_done && second_half_is_done { + return Err(Error::Overrun); + } + + let last_read_half = self.readable_half; + + Ok(match last_read_half { + Half::First => { + if second_half_is_done { + self.payload + .channel + .ifcr() + .write(|w| unsafe { w.ctcif::().set_bit() }); + + self.readable_half = Half::Second; + Half::Second + } else { + last_read_half + } + } + Half::Second => { + if first_half_is_done { + self.payload + .channel + .ifcr() + .write(|w| unsafe { w.chtif::().set_bit() }); + + self.readable_half = Half::First; + Half::First + } else { + last_read_half + } + } + }) + } + + /// Stops the transfer and returns the underlying buffer and RxDma + pub fn stop(mut self) -> (&'static mut [B; 2], RxDma>) { + self.payload.stop(); + + (self.buffer, self.payload) + } +} + +impl + Transfer>> +where + RxDma>: TransferPayload, +{ + pub fn is_done(&self) -> bool { + !self.payload.channel.in_progress() + } + + pub fn wait(mut self) -> (BUFFER, RxDma>) { + while !self.is_done() {} + + atomic::compiler_fence(Ordering::Acquire); + + self.payload.stop(); + + // we need a read here to make the Acquire fence effective + // we do *not* need this if `dma.stop` does a RMW operation + unsafe { + ptr::read_volatile(&0); + } + + // we need a fence here for the same reason we need one in `Transfer.wait` + atomic::compiler_fence(Ordering::Acquire); + + // `Transfer` needs to have a `Drop` implementation, because we accept + // managed buffers that can free their memory on drop. Because of that + // we can't move out of the `Transfer`'s fields, so we use `ptr::read` + // and `mem::forget`. + // + // NOTE(unsafe) There is no panic branch between getting the resources + // and forgetting `self`. + unsafe { + let buffer = ptr::read(&self.buffer); + let payload = ptr::read(&self.payload); + mem::forget(self); + (buffer, payload) + } + } +} + +impl + Transfer>> +where + TxDma>: TransferPayload, +{ + pub fn is_done(&self) -> bool { + !self.payload.channel.in_progress() + } + + pub fn wait(mut self) -> (BUFFER, TxDma>) { + while !self.is_done() {} + + atomic::compiler_fence(Ordering::Acquire); + + self.payload.stop(); + + // we need a read here to make the Acquire fence effective + // we do *not* need this if `dma.stop` does a RMW operation + unsafe { + ptr::read_volatile(&0); + } + + // we need a fence here for the same reason we need one in `Transfer.wait` + atomic::compiler_fence(Ordering::Acquire); + + // `Transfer` needs to have a `Drop` implementation, because we accept + // managed buffers that can free their memory on drop. Because of that + // we can't move out of the `Transfer`'s fields, so we use `ptr::read` + // and `mem::forget`. + // + // NOTE(unsafe) There is no panic branch between getting the resources + // and forgetting `self`. + unsafe { + let buffer = ptr::read(&self.buffer); + let payload = ptr::read(&self.payload); + mem::forget(self); + (buffer, payload) + } + } +} + +impl + Transfer, TXC>> +where + RxTxDma, TXC>: TransferPayload, +{ + pub fn is_done(&self) -> bool { + !self.payload.rxchannel.in_progress() + } + + pub fn wait(mut self) -> (BUFFER, RxTxDma, TXC>) { + while !self.is_done() {} + + atomic::compiler_fence(Ordering::Acquire); + + self.payload.stop(); + + // we need a read here to make the Acquire fence effective + // we do *not* need this if `dma.stop` does a RMW operation + unsafe { + ptr::read_volatile(&0); + } + + // we need a fence here for the same reason we need one in `Transfer.wait` + atomic::compiler_fence(Ordering::Acquire); + + // `Transfer` needs to have a `Drop` implementation, because we accept + // managed buffers that can free their memory on drop. Because of that + // we can't move out of the `Transfer`'s fields, so we use `ptr::read` + // and `mem::forget`. + // + // NOTE(unsafe) There is no panic branch between getting the resources + // and forgetting `self`. + unsafe { + let buffer = ptr::read(&self.buffer); + let payload = ptr::read(&self.payload); + mem::forget(self); + (buffer, payload) + } + } +} + +impl Transfer>> +where + RxDma>: TransferPayload, +{ + pub fn peek(&self) -> &[T] + where + BUFFER: AsRef<[T]>, + { + let pending = self.payload.channel.get_ndtr() as usize; + + let slice = self.buffer.as_ref(); + let capacity = slice.len(); + + &slice[..(capacity - pending)] + } +} + +impl + Transfer, TXC>> +where + RxTxDma, TXC>: TransferPayload, +{ + pub fn peek(&self) -> &[T] + where + RXBUFFER: AsRef<[T]>, + { + let pending = self.payload.rxchannel.get_ndtr() as usize; + + let slice = self.buffer.0.as_ref(); + let capacity = slice.len(); + + &slice[..(capacity - pending)] + } +} + +macro_rules! dma { + ($DMAX:ident: ($dmaX:ident, { + $($CX:ident: ($ch: literal),)+ + }),) => { + pub mod $dmaX { + use crate::dma::DmaExt; + use crate::pac::{$DMAX, RCC}; + + #[non_exhaustive] + #[allow(clippy::manual_non_exhaustive)] + pub struct Channels((), $(pub $CX),+); + + $( + pub type $CX = super::Ch<$DMAX, $ch>; + )+ + + impl DmaExt for $DMAX { + type Channels = Channels; + + fn split(self) -> Channels { + let rcc = unsafe { &(*RCC::ptr()) }; + // only 1 DMA for clock enable + rcc.ahbenr.modify(|_,w| w.dmaen().enabled()); + + // reset the DMA control registers (stops all on-going transfers) + $( + self.ch[$ch].cr.reset(); + )+ + + Channels((), $(super::Ch::<$DMAX, $ch>(super::PhantomData)),+) + } + + fn ptr() -> *const crate::pac::dma::RegisterBlock { + Self::ptr() + } + } + } + } +} + +#[cfg(any(feature = "py32f003", feature = "py32f030"))] +dma! { + DMA: (dma1, { + C1: (0), + C2: (1), + C3: (2), + }), +} + +/// DMA Receiver +pub struct RxDma { + pub(crate) payload: PAYLOAD, + pub channel: RXCH, +} + +/// DMA Transmitter +pub struct TxDma { + pub(crate) payload: PAYLOAD, + pub channel: TXCH, +} + +/// DMA Receiver/Transmitter +pub struct RxTxDma { + pub(crate) payload: PAYLOAD, + pub rxchannel: RXCH, + pub txchannel: TXCH, +} + +pub trait Receive { + type RxChannel; + type TransmittedWord; +} + +pub trait Transmit { + type TxChannel; + type ReceivedWord; +} + +/// Trait for circular DMA readings from peripheral to memory. +pub trait CircReadDma: Receive +where + &'static mut [B; 2]: WriteBuffer, + B: 'static, + Self: core::marker::Sized, +{ + fn circ_read(self, buffer: &'static mut [B; 2]) -> CircBuffer; +} + +/// Trait for DMA readings from peripheral to memory. +pub trait ReadDma: Receive +where + B: WriteBuffer, + Self: core::marker::Sized + TransferPayload, +{ + fn read(self, buffer: B) -> Transfer; +} + +/// Trait for DMA writing from memory to peripheral. +pub trait WriteDma: Transmit +where + B: ReadBuffer, + Self: core::marker::Sized + TransferPayload, +{ + fn write(self, buffer: B) -> Transfer; +} + +/// Trait for DMA simultaneously reading and writing within one synchronous operation. Panics if both buffers are not of equal length. +pub trait ReadWriteDma: Transmit +where + RXB: WriteBuffer, + TXB: ReadBuffer, + Self: core::marker::Sized + TransferPayload, +{ + fn read_write(self, rx_buffer: RXB, tx_buffer: TXB) -> Transfer; +} diff --git a/src/gpio.rs b/src/gpio.rs index c970818..61a1da1 100644 --- a/src/gpio.rs +++ b/src/gpio.rs @@ -87,7 +87,7 @@ pub struct Output { /// Push pull output (type state) pub struct PushPull; -use embedded_hal::digital::v2::{toggleable, InputPin, OutputPin, StatefulOutputPin}; +use embedded_hal::digital::{InputPin, OutputPin, StatefulOutputPin}; /// Fully erased pin pub struct Pin { @@ -104,19 +104,21 @@ unsafe impl Send for Pin {} impl StatefulOutputPin for Pin> { #[inline(always)] - fn is_set_high(&self) -> Result { + fn is_set_high(&mut self) -> Result { self.is_set_low().map(|v| !v) } #[inline(always)] - fn is_set_low(&self) -> Result { + fn is_set_low(&mut self) -> Result { Ok(unsafe { (*self.port).is_set_low(self.i) }) } } -impl OutputPin for Pin> { +impl embedded_hal::digital::ErrorType for Pin> { type Error = Infallible; +} +impl OutputPin for Pin> { #[inline(always)] fn set_high(&mut self) -> Result<(), Self::Error> { unsafe { (*self.port).set_high(self.i) }; @@ -130,32 +132,30 @@ impl OutputPin for Pin> { } } -impl toggleable::Default for Pin> {} - impl InputPin for Pin> { - type Error = Infallible; - #[inline(always)] - fn is_high(&self) -> Result { + fn is_high(&mut self) -> Result { self.is_low().map(|v| !v) } #[inline(always)] - fn is_low(&self) -> Result { + fn is_low(&mut self) -> Result { Ok(unsafe { (*self.port).is_low(self.i) }) } } -impl InputPin for Pin> { +impl embedded_hal::digital::ErrorType for Pin> { type Error = Infallible; +} +impl InputPin for Pin> { #[inline(always)] - fn is_high(&self) -> Result { + fn is_high(&mut self) -> Result { self.is_low().map(|v| !v) } #[inline(always)] - fn is_low(&self) -> Result { + fn is_low(&mut self) -> Result { Ok(unsafe { (*self.port).is_low(self.i) }) } } @@ -204,14 +204,12 @@ macro_rules! gpio { use core::marker::PhantomData; use core::convert::Infallible; - use embedded_hal::digital::v2::{InputPin, OutputPin, StatefulOutputPin, toggleable}; + use embedded_hal::digital::{InputPin, OutputPin, StatefulOutputPin}; use crate::{ rcc::Rcc, pac::$GPIOX }; - use cortex_m::interrupt::CriticalSection; - use super::{ Alternate, Analog, Floating, GpioExt, Input, OpenDrain, Output, PullDown, PullUp, PushPull, AF0, AF1, AF2, AF3, AF4, AF5, AF6, AF7, @@ -278,7 +276,7 @@ macro_rules! gpio { impl $PXi { /// Configures the pin to operate in AF0 mode pub fn into_alternate_af0( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 0); $PXi { _mode: PhantomData } @@ -286,7 +284,7 @@ macro_rules! gpio { /// Configures the pin to operate in AF1 mode pub fn into_alternate_af1( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 1); $PXi { _mode: PhantomData } @@ -294,7 +292,7 @@ macro_rules! gpio { /// Configures the pin to operate in AF2 mode pub fn into_alternate_af2( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 2); $PXi { _mode: PhantomData } @@ -302,7 +300,7 @@ macro_rules! gpio { /// Configures the pin to operate in AF3 mode pub fn into_alternate_af3( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 3); $PXi { _mode: PhantomData } @@ -310,7 +308,7 @@ macro_rules! gpio { /// Configures the pin to operate in AF4 mode pub fn into_alternate_af4( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 4); $PXi { _mode: PhantomData } @@ -318,7 +316,7 @@ macro_rules! gpio { /// Configures the pin to operate in AF5 mode pub fn into_alternate_af5( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 5); $PXi { _mode: PhantomData } @@ -326,7 +324,7 @@ macro_rules! gpio { /// Configures the pin to operate in AF6 mode pub fn into_alternate_af6( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 6); $PXi { _mode: PhantomData } @@ -334,7 +332,7 @@ macro_rules! gpio { /// Configures the pin to operate in AF7 mode pub fn into_alternate_af7( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 7); $PXi { _mode: PhantomData } @@ -342,7 +340,7 @@ macro_rules! gpio { /// Configures the pin to operate in AF8 mode pub fn into_alternate_af8( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 8); $PXi { _mode: PhantomData } @@ -350,7 +348,7 @@ macro_rules! gpio { /// Configures the pin to operate in AF9 mode pub fn into_alternate_af9( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 9); $PXi { _mode: PhantomData } @@ -358,7 +356,7 @@ macro_rules! gpio { /// Configures the pin to operate in AF10 mode pub fn into_alternate_af10( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 10); $PXi { _mode: PhantomData } @@ -366,7 +364,7 @@ macro_rules! gpio { /// Configures the pin to operate in AF11 mode pub fn into_alternate_af11( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 11); $PXi { _mode: PhantomData } @@ -374,7 +372,7 @@ macro_rules! gpio { /// Configures the pin to operate in AF12 mode pub fn into_alternate_af12( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 12); $PXi { _mode: PhantomData } @@ -382,7 +380,7 @@ macro_rules! gpio { /// Configures the pin to operate in AF13 mode pub fn into_alternate_af13( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 13); $PXi { _mode: PhantomData } @@ -390,7 +388,7 @@ macro_rules! gpio { /// Configures the pin to operate in AF14 mode pub fn into_alternate_af14( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 14); $PXi { _mode: PhantomData } @@ -398,7 +396,7 @@ macro_rules! gpio { /// Configures the pin to operate in AF15 mode pub fn into_alternate_af15( - self, _cs: &CriticalSection + self, ) -> $PXi> { _set_alternate_mode($i, 15); $PXi { _mode: PhantomData } @@ -406,7 +404,7 @@ macro_rules! gpio { /// Configures the pin to operate as a floating input pin pub fn into_floating_input( - self, _cs: &CriticalSection + self, ) -> $PXi> { let offset = 2 * $i; unsafe { @@ -423,7 +421,7 @@ macro_rules! gpio { /// Configures the pin to operate as a pulled down input pin pub fn into_pull_down_input( - self, _cs: &CriticalSection + self, ) -> $PXi> { let offset = 2 * $i; unsafe { @@ -440,7 +438,7 @@ macro_rules! gpio { /// Configures the pin to operate as a pulled up input pin pub fn into_pull_up_input( - self, _cs: &CriticalSection + self, ) -> $PXi> { let offset = 2 * $i; unsafe { @@ -457,7 +455,7 @@ macro_rules! gpio { /// Configures the pin to operate as an analog pin pub fn into_analog( - self, _cs: &CriticalSection + self, ) -> $PXi { let offset = 2 * $i; unsafe { @@ -474,7 +472,7 @@ macro_rules! gpio { /// Configures the pin to operate as an open drain output pin pub fn into_open_drain_output( - self, _cs: &CriticalSection + self, ) -> $PXi> { let offset = 2 * $i; unsafe { @@ -494,7 +492,7 @@ macro_rules! gpio { /// Configures the pin to operate as an push pull output pin pub fn into_push_pull_output( - self, _cs: &CriticalSection + self, ) -> $PXi> { let offset = 2 * $i; unsafe { @@ -515,7 +513,7 @@ macro_rules! gpio { /// Configures the pin to operate as an push pull output pin with quick fall /// and rise times pub fn into_push_pull_output_hs( - self, _cs: &CriticalSection + self, ) -> $PXi> { let offset = 2 * $i; unsafe { @@ -539,7 +537,7 @@ macro_rules! gpio { impl $PXi> { /// Enables / disables the internal pull up - pub fn internal_pull_up(&mut self, _cs: &CriticalSection, on: bool) { + pub fn internal_pull_up(&mut self, on: bool) { let offset = 2 * $i; let value = if on { 0b01 } else { 0b00 }; unsafe { @@ -553,7 +551,7 @@ macro_rules! gpio { impl $PXi> { /// Enables / disables the internal pull up - pub fn internal_pull_up(self, _cs: &CriticalSection, on: bool) -> Self { + pub fn internal_pull_up(self, on: bool) -> Self { let offset = 2 * $i; let value = if on { 0b01 } else { 0b00 }; unsafe { @@ -568,7 +566,7 @@ macro_rules! gpio { impl $PXi> { /// Turns pin alternate configuration pin into open drain - pub fn set_open_drain(self, _cs: &CriticalSection) -> Self { + pub fn set_open_drain(self) -> Self { let offset = $i; unsafe { let reg = &(*$GPIOX::ptr()); @@ -594,19 +592,21 @@ macro_rules! gpio { } } + impl embedded_hal::digital::ErrorType for $PXi> { + type Error = Infallible; + } + impl StatefulOutputPin for $PXi> { - fn is_set_high(&self) -> Result { + fn is_set_high(&mut self) -> Result { self.is_set_low().map(|v| !v) } - fn is_set_low(&self) -> Result { + fn is_set_low(&mut self) -> Result { Ok(unsafe { (*$GPIOX::ptr()).is_set_low($i) }) } } impl OutputPin for $PXi> { - type Error = Infallible; - fn set_high(&mut self) -> Result<(), Self::Error> { Ok(unsafe { (*$GPIOX::ptr()).set_high($i) }) } @@ -616,16 +616,12 @@ macro_rules! gpio { } } - impl toggleable::Default for $PXi> {} - impl InputPin for $PXi> { - type Error = Infallible; - - fn is_high(&self) -> Result { + fn is_high(&mut self) -> Result { self.is_low().map(|v| !v) } - fn is_low(&self) -> Result { + fn is_low(&mut self) -> Result { Ok(unsafe { (*$GPIOX::ptr()).is_low($i) }) } } @@ -644,14 +640,16 @@ macro_rules! gpio { } } - impl InputPin for $PXi> { + impl embedded_hal::digital::ErrorType for $PXi> { type Error = Infallible; + } - fn is_high(&self) -> Result { + impl InputPin for $PXi> { + fn is_high(&mut self) -> Result { self.is_low().map(|v| !v) } - fn is_low(&self) -> Result { + fn is_low(&mut self) -> Result { Ok(unsafe { (*$GPIOX::ptr()).is_low($i) }) } } diff --git a/src/lib.rs b/src/lib.rs index bf9fc52..6714e31 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -13,18 +13,18 @@ pub use py32f0::py32f003 as pac; #[cfg(feature = "py32f030")] pub use py32f0::py32f030 as pac; +//#[cfg(feature = "device-selected")] +//pub mod adc; #[cfg(feature = "device-selected")] -pub mod adc; -#[cfg(feature = "device-selected")] -pub mod delay; +pub mod dma; #[cfg(feature = "device-selected")] pub mod gpio; -#[cfg(feature = "device-selected")] -pub mod i2c; +//#[cfg(feature = "device-selected")] +//pub mod i2c; #[cfg(feature = "device-selected")] pub mod prelude; -#[cfg(feature = "device-selected")] -pub mod pwm; +//#[cfg(feature = "device-selected")] +//pub mod pwm; #[cfg(feature = "device-selected")] pub mod rcc; #[cfg(feature = "device-selected")] @@ -33,7 +33,7 @@ pub mod serial; pub mod spi; #[cfg(feature = "device-selected")] pub mod time; -#[cfg(feature = "device-selected")] -pub mod timers; -#[cfg(feature = "device-selected")] -pub mod watchdog; +//#[cfg(feature = "device-selected")] +//pub mod timers; +//#[cfg(feature = "device-selected")] +//pub mod watchdog; diff --git a/src/prelude.rs b/src/prelude.rs index d2f9ed1..58df03c 100644 --- a/src/prelude.rs +++ b/src/prelude.rs @@ -1,15 +1,12 @@ -pub use embedded_hal::prelude::*; - // TODO for some reason, watchdog isn't in the embedded_hal prelude -pub use embedded_hal::watchdog::Watchdog as _py32f0xx_hal_embedded_hal_watchdog_Watchdog; -pub use embedded_hal::watchdog::WatchdogEnable as _py32f0xx_hal_embedded_hal_watchdog_WatchdogEnable; +//pub use embedded_hal::watchdog::Watchdog as _py32f0xx_hal_embedded_hal_watchdog_Watchdog; +//pub use embedded_hal::watchdog::WatchdogEnable as _py32f0xx_hal_embedded_hal_watchdog_WatchdogEnable; -pub use embedded_hal::adc::OneShot as _embedded_hal_adc_OneShot; +//pub use embedded_hal::adc::OneShot as _embedded_hal_adc_OneShot; -pub use embedded_hal::digital::v2::InputPin as _embedded_hal_gpio_InputPin; -pub use embedded_hal::digital::v2::OutputPin as _embedded_hal_gpio_OutputPin; -pub use embedded_hal::digital::v2::StatefulOutputPin as _embedded_hal_gpio_StatefulOutputPin; -pub use embedded_hal::digital::v2::ToggleableOutputPin as _embedded_hal_gpio_ToggleableOutputPin; +pub use embedded_hal::digital::InputPin as _embedded_hal_gpio_InputPin; +pub use embedded_hal::digital::OutputPin as _embedded_hal_gpio_OutputPin; +pub use embedded_hal::digital::StatefulOutputPin as _embedded_hal_gpio_StatefulOutputPin; pub use crate::gpio::GpioExt as _py32f0xx_hal_gpio_GpioExt; pub use crate::rcc::RccExt as _py32f0xx_hal_rcc_RccExt; diff --git a/src/serial.rs b/src/serial.rs index 910481c..3c01d3e 100644 --- a/src/serial.rs +++ b/src/serial.rs @@ -59,13 +59,10 @@ //! ``` use core::{ - convert::Infallible, fmt::{Result, Write}, ops::Deref, }; -use embedded_hal::prelude::*; - use crate::gpio::{gpioa::*, gpiob::*}; use crate::gpio::{Alternate, AF1}; use crate::{rcc::Rcc, time::Bps}; @@ -103,6 +100,8 @@ pub enum Event { Txe, /// Idle line state detected Idle, + /// Transmission complete + Txc, } pub trait TxPin {} @@ -312,6 +311,9 @@ macro_rules! usart { Event::Idle => { self.usart.cr1.modify(|_, w| w.idleie().set_bit()) }, + Event::Txc => { + self.usart.cr1.modify(|_, w| w.tcie().set_bit()) + }, } } @@ -327,6 +329,9 @@ macro_rules! usart { Event::Idle => { self.usart.cr1.modify(|_, w| w.idleie().clear_bit()) }, + Event::Txc => { + self.usart.cr1.modify(|_, w| w.tcie().clear_bit()) + }, } } @@ -350,6 +355,49 @@ macro_rules! usart { self.usart.sr.read().tc().bit_is_set() } } + + impl Tx<$USART> { + + /// Starts listening for TXE interrupt event + pub fn listen_txe(&mut self) { + unsafe { (*self.usart).cr1.modify(|_, w| w.txeie().set_bit()) } + } + + /// Stop listening for TXE interrupt event + pub fn unlisten_txe(&mut self) { + unsafe { (*self.usart).cr1.modify(|_, w| w.txeie().clear_bit()) } + } + + /// Returns true if the rx register is not empty (and can be read) + pub fn is_txe(&self) -> bool { + unsafe { (*self.usart).sr.read().txe().bit_is_set() } + } + + /// Returns true if transmission is complete + pub fn is_tx_complete(&self) -> bool { + unsafe { (*self.usart).sr.read().tc().bit_is_set() } + } + } + + impl Rx<$USART> { + + /// Starts listening for RXNE interrupt event + pub fn listen_rxne(&mut self) { + unsafe { (*self.usart).cr1.modify(|_, w| w.rxneie().set_bit()) } + } + + /// Stop listening for RXNE interrupt event + pub fn unlisten_rxne(&mut self) { + unsafe { (*self.usart).cr1.modify(|_, w| w.rxneie().clear_bit()) } + } + + /// Returns true if the rx register is not empty (and can be read) + pub fn is_rx_not_empty(&self) -> bool { + unsafe { (*self.usart).sr.read().rxne().bit_is_set() } + } + + } + )+ } } @@ -369,37 +417,56 @@ usart! { USART2: (usart2, usart2tx, usart2rx,usart2en, apbenr1), } -impl embedded_hal::serial::Read for Rx +use embedded_hal_nb::{serial, serial::ErrorKind, serial::Write as OtherWrite}; + +impl serial::Error for Error { + fn kind(&self) -> ErrorKind { + match self { + Error::Overrun => ErrorKind::Overrun, + Error::Framing => ErrorKind::FrameFormat, + Error::Parity => ErrorKind::Parity, + Error::Noise => ErrorKind::Noise, + } + } +} + +impl serial::ErrorType for Rx { + type Error = Error; +} + +impl embedded_hal_nb::serial::Read for Rx where USART: Deref, { - type Error = Error; - /// Tries to read a byte from the uart - fn read(&mut self) -> nb::Result { + fn read(&mut self) -> nb::Result { read(self.usart) } } -impl embedded_hal::serial::Read for Serial +impl serial::ErrorType for Serial { + type Error = Error; +} + +impl embedded_hal_nb::serial::Read for Serial where USART: Deref, RXPIN: RxPin, { - type Error = Error; - /// Tries to read a byte from the uart - fn read(&mut self) -> nb::Result { + fn read(&mut self) -> nb::Result { read(&*self.usart) } } -impl embedded_hal::serial::Write for Tx +impl serial::ErrorType for Tx { + type Error = Error; +} + +impl embedded_hal_nb::serial::Write for Tx where USART: Deref, { - type Error = Infallible; - /// Ensures that none of the previously written words are still buffered fn flush(&mut self) -> nb::Result<(), Self::Error> { flush(self.usart) @@ -412,13 +479,11 @@ where } } -impl embedded_hal::serial::Write for Serial +impl embedded_hal_nb::serial::Write for Serial where USART: Deref, TXPIN: TxPin, { - type Error = Infallible; - /// Ensures that none of the previously written words are still buffered fn flush(&mut self) -> nb::Result<(), Self::Error> { flush(&*self.usart) @@ -461,7 +526,7 @@ where impl Write for Tx where - Tx: embedded_hal::serial::Write, + Tx: embedded_hal_nb::serial::Write, { fn write_str(&mut self, s: &str) -> Result { s.as_bytes() @@ -485,7 +550,7 @@ where } /// Ensures that none of the previously written words are still buffered -fn flush(usart: *const SerialRegisterBlock) -> nb::Result<(), Infallible> { +fn flush(usart: *const SerialRegisterBlock) -> nb::Result<(), Error> { // NOTE(unsafe) atomic read with no side effects let sr = unsafe { (*usart).sr.read() }; @@ -498,13 +563,13 @@ fn flush(usart: *const SerialRegisterBlock) -> nb::Result<(), Infallible> { /// Tries to write a byte to the UART /// Returns `Err(WouldBlock)` if the transmit buffer is full -fn write(usart: *const SerialRegisterBlock, byte: u8) -> nb::Result<(), Infallible> { +fn write(usart: *const SerialRegisterBlock, byte: u8) -> nb::Result<(), Error> { // NOTE(unsafe) atomic read with no side effects let sr = unsafe { (*usart).sr.read() }; if sr.txe().bit_is_set() { // NOTE(unsafe) atomic write to stateless register - unsafe { (*usart).dr.write(|w| w.dr().bits(byte as u16)) } + unsafe { (*usart).dr8().write(|w| w.dr().bits(byte)) } Ok(()) } else { Err(nb::Error::WouldBlock) @@ -516,7 +581,7 @@ fn read(usart: *const SerialRegisterBlock) -> nb::Result { // NOTE(unsafe) atomic read with no side effects let sr = unsafe { (*usart).sr.read() }; - let dr = unsafe { (*usart).dr.read() }; + let dr = unsafe { (*usart).dr8().read() }; if sr.pe().bit_is_set() { Err(nb::Error::Other(Error::Parity)) diff --git a/src/spi.rs b/src/spi.rs index 5128322..8fbdfd7 100644 --- a/src/spi.rs +++ b/src/spi.rs @@ -1,3 +1,5 @@ +#![allow(dead_code)] + //! API for the integrate SPI peripherals //! //! The spi bus acts as the master (generating the clock) and you need to handle the CS separately. @@ -37,11 +39,10 @@ //! }); //! ``` -use core::cell::UnsafeCell; use core::marker::PhantomData; -use core::{ops::Deref, ptr}; +use core::ops::Deref; -pub use embedded_hal::spi::{Mode, Phase, Polarity}; +pub use embedded_hal::spi::{ErrorKind, Mode, Phase, Polarity}; // TODO Put this inside the macro // Currently that causes a compiler panic @@ -73,6 +74,16 @@ pub enum Error { Crc, } +impl ::embedded_hal::spi::Error for Error { + fn kind(&self) -> ErrorKind { + match self { + Error::Overrun => ErrorKind::Overrun, + Error::ModeFault => ErrorKind::ModeFault, + Error::Crc => ErrorKind::Other, + } + } +} + /// SPI abstraction pub struct Spi { spi: SPI, @@ -400,103 +411,79 @@ where pub fn release(self) -> (SPI, (SCKPIN, MISOPIN, MOSIPIN)) { (self.spi, self.pins) } + + pub fn ptr(&self) -> *const SpiRegisterBlock { + self.spi.deref() + } } -impl ::embedded_hal::blocking::spi::Transfer +impl ::embedded_hal::spi::ErrorType for Spi where SPI: Deref, { type Error = Error; +} - fn transfer<'w>(&mut self, words: &'w mut [u8]) -> Result<&'w [u8], Self::Error> { +impl ::embedded_hal::spi::SpiBus + for Spi +where + SPI: Deref, +{ + fn read(&mut self, words: &mut [u8]) -> Result<(), Self::Error> { // We want to transfer bidirectionally, make sure we're in the correct mode self.set_bidi(); for word in words.iter_mut() { nb::block!(self.check_send())?; - self.send_u8(*word); + self.send_u8(0xFF); nb::block!(self.check_read())?; *word = self.read_u8(); } - - Ok(words) + Ok(()) } -} - -impl ::embedded_hal::blocking::spi::Write - for Spi -where - SPI: Deref, -{ - type Error = Error; fn write(&mut self, words: &[u8]) -> Result<(), Self::Error> { - let mut bufcap: u8 = 0; - - // We only want to send, so we don't need to worry about the receive buffer overflowing self.set_send_only(); - - // Make sure we don't continue with an error condition - nb::block!(self.check_send())?; - - // We have a 32 bit buffer to work with, so let's fill it before checking the status - for word in words { - // Loop as long as our send buffer is full - while bufcap == 0 { - bufcap = self.send_buffer_size(); - } - + for word in words.iter() { + nb::block!(self.check_send())?; self.send_u8(*word); - bufcap -= 1; + nb::block!(self.check_read())?; + self.read_u8(); } - - // Do one last status register check before continuing - nb::block!(self.check_send()).ok(); Ok(()) } -} - -impl ::embedded_hal::blocking::spi::Transfer - for Spi -where - SPI: Deref, -{ - type Error = Error; - fn transfer<'w>(&mut self, words: &'w mut [u16]) -> Result<&'w [u16], Self::Error> { + fn transfer(&mut self, read: &mut [u8], write: &[u8]) -> Result<(), Self::Error> { // We want to transfer bidirectionally, make sure we're in the correct mode self.set_bidi(); - for word in words.iter_mut() { + for (rd_word, wr_word) in read.iter_mut().zip(write.iter()) { nb::block!(self.check_send())?; - self.send_u16(*word); + self.send_u8(*wr_word); nb::block!(self.check_read())?; - *word = self.read_u16(); + *rd_word = self.read_u8(); } - Ok(words) + Ok(()) } -} -impl ::embedded_hal::blocking::spi::Write - for Spi -where - SPI: Deref, -{ - type Error = Error; - - fn write(&mut self, words: &[u16]) -> Result<(), Self::Error> { - // We only want to send, so we don't need to worry about the receive buffer overflowing - self.set_send_only(); + fn transfer_in_place(&mut self, words: &mut [u8]) -> Result<(), Self::Error> { + // We want to transfer bidirectionally, make sure we're in the correct mode + self.set_bidi(); - for word in words { + for word in words.iter_mut() { nb::block!(self.check_send())?; - self.send_u16(*word); + self.send_u8(*word); + nb::block!(self.check_read())?; + *word = self.read_u8(); } - // Do one last status register check before continuing - nb::block!(self.check_send()).ok(); + Ok(()) + } + + fn flush(&mut self) -> Result<(), Self::Error> { + // no delays required after reads for bus to be idle Ok(()) } } From b6fca6fb16652ddd27d0747a790e7a728eb84b16 Mon Sep 17 00:00:00 2001 From: Greg Green Date: Sat, 23 Nov 2024 12:14:14 -0800 Subject: [PATCH 02/11] Converting to use embedded-hal 1.0 Added embedded-hal 1.0, embedded-hal-nb 1.0, embedded-io 0.6 Renamed embedded-hal 0.2.7 to embedded-hal-02 Added 'with-dma' feature to ease code use with dma module adc module now uses embedded-hal-02 only delay module uses embedded-hal-02 only Added peripheral mapping to dma module Fixed bug with clearing DMA flags for a channel Changed types of DMA channels to use channel numbers from 1-3 instead of the array offsets 0-2, eases downstream code use Converted gpio mod to use embedded-hal 1 and 0.2 both Added EXTI interrupt code to gpio mod. Added port identifier to Pin structs for use in EXTI setup i2c module uses embedded-hal-02 only Adjusted prelude mod to remove embedded-hal traits pwm mod uses embedded-hal-02 only Added enable mod to rcc mod. Added traits BusClock, BusTimerClock, Enable, Reset to rcc mod enable module also seals all peripherals serial mod uses embedded-hal 1 and 0.2 both, and can use DMA spi mod uses embedded-hal 1 and 0.2 both, and can use DMA spi now has slave functions, but not tested timers mod uses embedded-hal 0.2 only watchdog mod uses embedded-hal 0.2 only --- Cargo.toml | 36 +- openocd.cfg | 2 +- src/adc.rs | 21 +- src/delay.rs | 125 +++++ src/dma.rs | 118 ++++- src/gpio.rs | 318 ++++++++---- src/gpio/hal_02.rs | 214 ++++++++ src/gpio/hal_1.rs | 175 +++++++ src/i2c.rs | 2 +- src/lib.rs | 27 +- src/prelude.rs | 22 +- src/pwm.rs | 4 +- src/rcc.rs | 152 +++++- src/rcc/enable.rs | 98 ++++ src/serial.rs | 1157 +++++++++++++++++++++++++++++------------- src/serial/hal_02.rs | 132 +++++ src/serial/hal_1.rs | 162 ++++++ src/spi.rs | 748 +++++++++++++++++---------- src/spi/dma.rs | 658 ++++++++++++++++++++++++ src/spi/hal_02.rs | 70 +++ src/spi/hal_1.rs | 96 ++++ src/timers.rs | 2 +- src/watchdog.rs | 4 +- 23 files changed, 3529 insertions(+), 814 deletions(-) create mode 100644 src/delay.rs create mode 100644 src/gpio/hal_02.rs create mode 100644 src/gpio/hal_1.rs create mode 100644 src/rcc/enable.rs create mode 100644 src/serial/hal_02.rs create mode 100644 src/serial/hal_1.rs create mode 100644 src/spi/dma.rs create mode 100644 src/spi/hal_02.rs create mode 100644 src/spi/hal_1.rs diff --git a/Cargo.toml b/Cargo.toml index 668c9af..ee6e520 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -1,20 +1,21 @@ [package] -edition = "2018" +name = "py32f0xx-hal" +version = "0.2.0" authors = [ "Daniel Egger ", "Thomas Bytheway ", "Jesse Braham ", ] -categories = ["embedded", "hardware-support", "no-std"] -description = "Peripheral access API for py32F0 series microcontrollers" -documentation = "https://docs.rs/crate/py32f0xx-hal" +edition = "2018" +rust-version = "1.59" keywords = ["arm", "cortex-m", "py32f0xx", "hal"] license = "0BSD" -name = "py32f0xx-hal" readme = "README.md" repository = "https://github.com/creatoy/py32f0xx-hal" -version = "0.1.1" +categories = ["embedded", "hardware-support", "no-std"] +description = "Peripheral access API for py32F0 series microcontrollers" +documentation = "https://docs.rs/crate/py32f0xx-hal" [package.metadata.docs.rs] features = ["py32f030", "rt"] @@ -24,13 +25,25 @@ targets = ["thumbv6m-none-eabi"] bare-metal = { version = "1.0.0" } cast = "0.3.0" cortex-m = { version = "0.7.7", features = ["critical-section-single-core"] } -embedded-hal = "1.0.0" embedded-time = "0.12.1" -embedded-hal-nb = "1.0.0" embedded-dma = "0.2.0" nb = "1.1.0" void = { version = "1.0.2", default-features = false } +[dependencies.embedded-hal-02] +package = "embedded-hal" +version = "0.2.7" +features = ["unproven"] + +[dependencies.embedded-hal] +version = "1.0" + +[dependencies.embedded-hal-nb] +version = "1.0" + +[dependencies.embedded-io] +version = "0.6.1" + [dependencies.py32f0] version = "0.1.1" features = [] @@ -47,8 +60,8 @@ mfrc522 = "0.6.1" [features] device-selected = [] rt = ["py32f0/rt"] -py32f030 = ["py32f0/py32f030", "device-selected"] -py32f003 = ["py32f0/py32f003", "device-selected"] +py32f030 = ["py32f0/py32f030", "device-selected", "with-dma"] +py32f003 = ["py32f0/py32f003", "device-selected", "with-dma"] py32f002a = ["py32f0/py32f002a", "device-selected"] py32f002b = ["py32f0/py32f002b", "device-selected"] @@ -67,6 +80,9 @@ ram-4 = [] ram-6 = [] ram-8 = [] +# optional peripherals +with-dma = [] + # MCU aliases # # Features correspond specific mcu series diff --git a/openocd.cfg b/openocd.cfg index 755e7c1..2e7673e 100644 --- a/openocd.cfg +++ b/openocd.cfg @@ -1,5 +1,5 @@ source [find interface/cmsis-dap.cfg] -source [find target/stm32f0x.cfg] +source [find target/py32f0x.cfg] init flash probe 0 diff --git a/src/adc.rs b/src/adc.rs index 285471c..78674f9 100644 --- a/src/adc.rs +++ b/src/adc.rs @@ -47,7 +47,7 @@ const VTEMPVAL_DELTA: u16 = VTEMPVAL_HIGH - VTEMPVAL_LOW; use core::ptr; -use embedded_hal::{ +use embedded_hal_02::{ adc::{Channel, OneShot}, blocking::delay::DelayUs, }; @@ -58,8 +58,8 @@ use crate::{ pac::{ adc::{ cfgr1::{ALIGN_A, RES_A}, - smpr::SMP_A, cfgr2::CKMODE_A, + smpr::SMP_A, }, ADC, }, @@ -318,7 +318,8 @@ impl VTemp { fn convert_temp(vtemp: u16) -> i16 { let vtempcal_low = unsafe { ptr::read(VTEMPCAL_LOW) } as i32; let vtempcal_high = unsafe { ptr::read(VTEMPCAL_HIGH) } as i32; - ((vtemp as i32 - vtempcal_low) * 100 * (VTEMPVAL_DELTA as i32) / (vtempcal_high - vtempcal_low) + ((vtemp as i32 - vtempcal_low) * 100 * (VTEMPVAL_DELTA as i32) + / (vtempcal_high - vtempcal_low) + 3000) as i16 } @@ -397,7 +398,7 @@ impl VRef { }; adc.restore_cfg(prev_cfg); - + ((u32::from(VREFINT_VAL) * 4095) / vref_val) as u16 } } @@ -520,14 +521,18 @@ impl Adc { while self.rb.cr.read().adcal().is_calibrating() {} #[cfg(any(feature = "py32f030", feature = "py32f003"))] - self.rb.cfgr1.modify(|_, w| w.dmacfg().bit(dmacfg).dmaen().bit(dmaen)); + self.rb + .cfgr1 + .modify(|_, w| w.dmacfg().bit(dmacfg).dmaen().bit(dmaen)); } fn select_clock(&mut self, rcc: &mut Rcc, ckmode: AdcClockMode) { rcc.regs.apbrstr2.modify(|_, w| w.adcrst().reset()); rcc.regs.apbrstr2.modify(|_, w| w.adcrst().clear_bit()); rcc.regs.apbenr2.modify(|_, w| w.adcen().enabled()); - self.rb.cfgr2.modify(|_, w| w.ckmode().variant(ckmode.into())); + self.rb + .cfgr2 + .modify(|_, w| w.ckmode().variant(ckmode.into())); } /// Apply config settings @@ -540,9 +545,9 @@ impl Adc { .variant(self.precision.into()) .align() .variant(self.align.into()) - .wait().disabled() + .wait() + .disabled() }); - } fn power_up(&mut self, chan: u8) { diff --git a/src/delay.rs b/src/delay.rs new file mode 100644 index 0000000..9cc27dc --- /dev/null +++ b/src/delay.rs @@ -0,0 +1,125 @@ +//! API for delays with the systick timer +//! +//! Please be aware of potential overflows when using `delay_us`. +//! E.g. at 48MHz the maximum delay is 89 seconds. +//! +//! Consider using the timers api as a more flexible interface +//! +//! # Example +//! +//! ``` no_run +//! use py32f0xx_hal as hal; +//! +//! use crate::hal::pac; +//! use crate::hal::prelude::*; +//! use crate::hal::delay::Delay; +//! use cortex_m::peripheral::Peripherals; +//! +//! let mut p = pac::Peripherals::take().unwrap(); +//! let mut cp = cortex_m::Peripherals::take().unwrap(); +//! +//! let mut rcc = p.RCC.configure().freeze(&mut p.FLASH); +//! let mut delay = Delay::new(cp.SYST, &rcc); +//! loop { +//! delay.delay_ms(1_000_u16); +//! } +//! ``` + +use cast::{u16, u32}; +use cortex_m::peripheral::syst::SystClkSource; +use cortex_m::peripheral::SYST; + +use crate::rcc::Rcc; + +use embedded_hal_02::blocking::delay::{DelayMs, DelayUs}; + +/// System timer (SysTick) as a delay provider +#[derive(Clone)] +pub struct Delay { + scale: u32, +} + +const SYSTICK_RANGE: u32 = 0x0100_0000; + +impl Delay { + /// Configures the system timer (SysTick) as a delay provider + pub fn new(mut syst: SYST, rcc: &Rcc) -> Delay { + syst.set_clock_source(SystClkSource::Core); + + syst.set_reload(SYSTICK_RANGE - 1); + syst.clear_current(); + syst.enable_counter(); + + assert!(rcc.clocks.hclk().0 >= 1_000_000); + let scale = rcc.clocks.hclk().0 / 1_000_000; + + Delay { scale } + // As access to the count register is possible without a reference to the systick, we can + // just drop it + } +} + +impl DelayMs for Delay { + // At 48 MHz (the maximum frequency), calling delay_us with ms * 1_000 directly overflows at 0x15D86 (just over the max u16 value) + // So we implement a separate, higher level, delay loop + fn delay_ms(&mut self, mut ms: u32) { + const MAX_MS: u32 = 0x0000_FFFF; + while ms != 0 { + let current_ms = if ms <= MAX_MS { ms } else { MAX_MS }; + self.delay_us(current_ms * 1_000); + ms -= current_ms; + } + } +} + +impl DelayMs for Delay { + fn delay_ms(&mut self, ms: u16) { + // Call delay_us directly, so we don't have to use the additional + // delay loop the u32 variant uses + self.delay_us(u32(ms) * 1_000); + } +} + +impl DelayMs for Delay { + fn delay_ms(&mut self, ms: u8) { + self.delay_ms(u16(ms)); + } +} + +// At 48MHz (the maximum frequency), this overflows at approx. 2^32 / 48 = 89 seconds +impl DelayUs for Delay { + fn delay_us(&mut self, us: u32) { + // The SysTick Reload Value register supports values between 1 and 0x00FFFFFF. + // Here less than maximum is used so we have some play if there's a long running interrupt. + const MAX_TICKS: u32 = 0x007F_FFFF; + + let mut total_ticks = us * self.scale; + + while total_ticks != 0 { + let current_ticks = if total_ticks <= MAX_TICKS { + total_ticks + } else { + MAX_TICKS + }; + + let start_count = SYST::get_current(); + total_ticks -= current_ticks; + + // Use the wrapping substraction and the modulo to deal with the systick wrapping around + // from 0 to 0xFFFF + while (start_count.wrapping_sub(SYST::get_current()) % SYSTICK_RANGE) < current_ticks {} + } + } +} + +impl DelayUs for Delay { + fn delay_us(&mut self, us: u16) { + self.delay_us(u32(us)) + } +} + +impl DelayUs for Delay { + fn delay_us(&mut self, us: u8) { + self.delay_us(u32(us)) + } +} diff --git a/src/dma.rs b/src/dma.rs index 8bbc76f..a8e89b0 100644 --- a/src/dma.rs +++ b/src/dma.rs @@ -79,6 +79,71 @@ impl core::convert::From for u8 { } } +#[derive(Clone, Copy, Debug, PartialEq, Eq)] +pub enum PeriphMap { + Adc, + Spi1Tx, + Spi1Rx, + Spi2Tx, + Spi2Rx, + Usart1Tx, + Usart1Rx, + Usart2Tx, + Usart2Rx, + I2cTx, + I2cRx, + Tim1Ch1, + Tim1Ch2, + Tim1Ch3, + Tim1Ch4, + Tim1Com, + Tim1Up, + Tim1Trig, + Tim3Ch1, + Tim3Ch3, + Tim3Ch4, + Tim3Trig, + Tim3Up, + Tim16Ch1, + Tim16Up, + Tim17Ch1, + Tim17Up, +} + +impl core::convert::From for u32 { + fn from(val: PeriphMap) -> u32 { + match val { + PeriphMap::Adc => 0, + PeriphMap::Spi1Tx => 1, + PeriphMap::Spi1Rx => 2, + PeriphMap::Spi2Tx => 3, + PeriphMap::Spi2Rx => 4, + PeriphMap::Usart1Tx => 5, + PeriphMap::Usart1Rx => 6, + PeriphMap::Usart2Tx => 7, + PeriphMap::Usart2Rx => 8, + PeriphMap::I2cTx => 9, + PeriphMap::I2cRx => 10, + PeriphMap::Tim1Ch1 => 11, + PeriphMap::Tim1Ch2 => 12, + PeriphMap::Tim1Ch3 => 13, + PeriphMap::Tim1Ch4 => 14, + PeriphMap::Tim1Com => 15, + PeriphMap::Tim1Up => 16, + PeriphMap::Tim1Trig => 17, + PeriphMap::Tim3Ch1 => 18, + PeriphMap::Tim3Ch3 => 19, + PeriphMap::Tim3Ch4 => 20, + PeriphMap::Tim3Trig => 21, + PeriphMap::Tim3Up => 22, + PeriphMap::Tim16Ch1 => 24, + PeriphMap::Tim16Up => 25, + PeriphMap::Tim17Ch1 => 26, + PeriphMap::Tim17Up => 27, + } + } +} + pub struct CircBuffer where BUFFER: 'static, @@ -173,6 +238,18 @@ pub struct W; pub struct Ch(PhantomData); impl Ch { + /// Set the Dma request `map` to the specified peripheral + pub fn set_map(&mut self, map: PeriphMap) { + unsafe { + (*pac::SYSCFG::ptr()).cfgr3.modify(|r, w| { + w.bits( + (r.bits() & !(0x1f << ((C - 1) * 8))) + | (Into::::into(map) << ((C - 1) * 8)), + ) + }); + } + } + /// Associated peripheral `address` /// /// `inc` indicates whether the address will be incremented after every byte transfer @@ -204,12 +281,19 @@ impl Ch { /// Starts the DMA transfer pub fn start(&mut self) { + // TODO: clear all the flags for a channel. There is no + // channel way of clearing the flags yet, so manipulate + // the bits directly, not ideal + // need an indexing method in the pac + self.ifcr() + .write(|w| unsafe { w.bits(0xF << ((C - 1) * 4)) }); self.ch().cr.modify(|_, w| w.en().set_bit()); } /// Stops the DMA transfer pub fn stop(&mut self) { - self.ifcr().write(|w| unsafe { w.cgif::().clear() }); + // TODO: do bit ops to get cgif flag cleared, until pac has indexing method + self.ifcr().write(|w| unsafe { w.bits(1 << ((C - 1) * 4)) }); self.ch().cr.modify(|_, w| w.en().clear_bit()); } @@ -233,7 +317,7 @@ impl Ch { } pub fn ch(&mut self) -> &pac::dma::CH { - unsafe { &(*DMA::ptr()).ch[C as usize] } + unsafe { &(*DMA::ptr()).ch[C as usize - 1] } } pub fn isr(&self) -> pac::dma::isr::R { @@ -247,7 +331,7 @@ impl Ch { pub fn get_ndtr(&self) -> u32 { // NOTE(unsafe) atomic read with no side effects - unsafe { (*DMA::ptr()).ch[C as usize].ndtr.read().bits() } + unsafe { (*DMA::ptr()).ch[C as usize - 1].ndtr.read().bits() } } } @@ -301,7 +385,8 @@ where self.payload .channel .ifcr() - .write(|w| unsafe { w.ctcif::().set_bit() }); + // TODO: do bit ops to get ctif flag cleared, until pac has indexing method + .write(|w| unsafe { w.bits(1 << (((C - 1) * 4) + 1)) }); self.readable_half = Half::Second; Half::Second @@ -314,7 +399,8 @@ where self.payload .channel .ifcr() - .write(|w| unsafe { w.chtif::().set_bit() }); + // TODO: do bit ops to get htif flag cleared, until pac has indexing method + .write(|w| unsafe { w.bits(1 << (((C - 1) * 4) + 2)) }); self.readable_half = Half::First; Half::First @@ -415,16 +501,16 @@ where } } -impl - Transfer, TXC>> +impl + Transfer, Ch>> where - RxTxDma, TXC>: TransferPayload, + RxTxDma, Ch>: TransferPayload, { pub fn is_done(&self) -> bool { !self.payload.rxchannel.in_progress() } - pub fn wait(mut self) -> (BUFFER, RxTxDma, TXC>) { + pub fn wait(mut self) -> (BUFFER, RxTxDma, Ch>) { while !self.is_done() {} atomic::compiler_fence(Ordering::Acquire); @@ -473,10 +559,10 @@ where } } -impl - Transfer, TXC>> +impl + Transfer, Ch>> where - RxTxDma, TXC>: TransferPayload, + RxTxDma, Ch>: TransferPayload, { pub fn peek(&self) -> &[T] where @@ -517,7 +603,7 @@ macro_rules! dma { // reset the DMA control registers (stops all on-going transfers) $( - self.ch[$ch].cr.reset(); + self.ch[$ch - 1].cr.reset(); )+ Channels((), $(super::Ch::<$DMAX, $ch>(super::PhantomData)),+) @@ -534,9 +620,9 @@ macro_rules! dma { #[cfg(any(feature = "py32f003", feature = "py32f030"))] dma! { DMA: (dma1, { - C1: (0), - C2: (1), - C3: (2), + C1: (1), + C2: (2), + C3: (3), }), } diff --git a/src/gpio.rs b/src/gpio.rs index 61a1da1..5537c78 100644 --- a/src/gpio.rs +++ b/src/gpio.rs @@ -1,9 +1,20 @@ //! General Purpose Input / Output -use core::convert::Infallible; use core::marker::PhantomData; -use crate::rcc::Rcc; +use crate::pac; + +mod hal_1; + +pub trait PinExt { + type Mode; + + /// Return pin number + fn pin_id(&self) -> u8; + + /// Return port + fn port_id(&self) -> u8; +} /// Extension trait to split a GPIO peripheral in independent pins and registers pub trait GpioExt { @@ -11,7 +22,15 @@ pub trait GpioExt { type Parts; /// Splits the GPIO block into independent pins and registers - fn split(self, rcc: &mut Rcc) -> Self::Parts; + /// + /// This resets the state of the GPIO block + fn split(self) -> Self::Parts; + + /// Splits the GPIO block into independent pins and registers without resetting its state + /// + /// # Safety + /// Make sure that all pins modes are set in reset state. + unsafe fn split_without_reset(self) -> Self::Parts; } trait GpioRegExt { @@ -21,6 +40,130 @@ trait GpioRegExt { fn set_low(&self, pos: u8); } +// Using SCREAMING_SNAKE_CASE to be consistent with other HALs +// see 59b2740 and #125 for motivation +#[allow(non_camel_case_types)] +#[derive(Debug, PartialEq, Eq, Clone, Copy)] +pub enum Edge { + Rising, + Falling, + RisingFalling, +} + +mod sealed { + /// Marker trait that show if `ExtiPin` can be implemented + pub trait Interruptable {} +} + +use sealed::Interruptable; + +impl Interruptable for Input {} + +/// External Interrupt Pin +pub trait ExtiPin { + fn make_interrupt_source(&mut self, exti: &mut pac::EXTI); + fn trigger_on_edge(&mut self, exti: &mut pac::EXTI, level: Edge); + fn enable_interrupt(&mut self, exti: &mut pac::EXTI); + fn disable_interrupt(&mut self, exti: &mut pac::EXTI); + fn clear_interrupt_pending_bit(&mut self); + fn check_interrupt(&self) -> bool; +} + +impl ExtiPin for PIN +where + PIN: PinExt, + PIN::Mode: Interruptable, +{ + /// Make corresponding EXTI line sensitive to this pin + fn make_interrupt_source(&mut self, exti: &mut pac::EXTI) { + let pin_number = self.pin_id(); + let offset = 8 * (pin_number % 4); + let port = match self.port_id() { + b'A' => 0, + b'B' => 1, + b'C' | b'F' => 2, + _ => unreachable!(), + }; + match pin_number { + // for pins 0-3, mux selects ports a=0, b=1, or f=2 + // for py32f002b, a=0, b=1, c=2 + 0..=3 => { + exti.exticr1.modify(|r, w| unsafe { + w.bits((r.bits() & !(0xf << offset)) | (port << offset)) + }); + } + // pin 4 is same as pins 0-3 + 4 => { + exti.exticr2.modify(|r, w| unsafe { + w.bits((r.bits() & !(0xf << offset)) | (port << offset)) + }); + } + // pins 5-7, mux selects ports a=0, b=1 + 5..=7 => { + exti.exticr2 + .modify(|r, w| unsafe { w.bits(r.bits() | (port << offset)) }); + } + // BUGBUG: py32f002a only has 8 pins? pin 8, mux selects ports a=0, b=1 + #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] + 8 => { + exti.exticr3 + .modify(|r, w| unsafe { w.bits(r.bits() | (port << offset)) }); + } + // BUGBUG: py32f002a only has 8 pins? pin 9-15, no mux + #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] + 9..=15 => {} + _ => unreachable!(), + } + } + + /// Generate interrupt on rising edge, falling edge or both + fn trigger_on_edge(&mut self, exti: &mut pac::EXTI, edge: Edge) { + let pin_number = self.pin_id(); + match edge { + Edge::Rising => { + exti.rtsr + .modify(|r, w| unsafe { w.bits(r.bits() | (1 << pin_number)) }); + exti.ftsr + .modify(|r, w| unsafe { w.bits(r.bits() & !(1 << pin_number)) }); + } + Edge::Falling => { + exti.rtsr + .modify(|r, w| unsafe { w.bits(r.bits() & !(1 << pin_number)) }); + exti.ftsr + .modify(|r, w| unsafe { w.bits(r.bits() | (1 << pin_number)) }); + } + Edge::RisingFalling => { + exti.rtsr + .modify(|r, w| unsafe { w.bits(r.bits() | (1 << pin_number)) }); + exti.ftsr + .modify(|r, w| unsafe { w.bits(r.bits() | (1 << pin_number)) }); + } + } + } + + /// Enable external interrupts from this pin. + fn enable_interrupt(&mut self, exti: &mut pac::EXTI) { + exti.imr + .modify(|r, w| unsafe { w.bits(r.bits() | (1 << self.pin_id())) }); + } + + /// Disable external interrupts from this pin + fn disable_interrupt(&mut self, exti: &mut pac::EXTI) { + exti.imr + .modify(|r, w| unsafe { w.bits(r.bits() & !(1 << self.pin_id())) }); + } + + /// Clear the interrupt pending bit for this pin + fn clear_interrupt_pending_bit(&mut self) { + unsafe { (*pac::EXTI::ptr()).pr.write(|w| w.bits(1 << self.pin_id())) }; + } + + /// Reads the interrupt pending bit for this pin + fn check_interrupt(&self) -> bool { + unsafe { ((*pac::EXTI::ptr()).pr.read().bits() & (1 << self.pin_id())) != 0 } + } +} + /// Alternate function 0 pub struct AF0; /// Alternate function 1 @@ -87,11 +230,10 @@ pub struct Output { /// Push pull output (type state) pub struct PushPull; -use embedded_hal::digital::{InputPin, OutputPin, StatefulOutputPin}; - /// Fully erased pin pub struct Pin { i: u8, + p: u8, port: *const dyn GpioRegExt, _mode: PhantomData, } @@ -102,61 +244,15 @@ unsafe impl Sync for Pin {} // threads unsafe impl Send for Pin {} -impl StatefulOutputPin for Pin> { - #[inline(always)] - fn is_set_high(&mut self) -> Result { - self.is_set_low().map(|v| !v) - } - - #[inline(always)] - fn is_set_low(&mut self) -> Result { - Ok(unsafe { (*self.port).is_set_low(self.i) }) - } -} - -impl embedded_hal::digital::ErrorType for Pin> { - type Error = Infallible; -} +impl PinExt for Pin { + type Mode = MODE; -impl OutputPin for Pin> { - #[inline(always)] - fn set_high(&mut self) -> Result<(), Self::Error> { - unsafe { (*self.port).set_high(self.i) }; - Ok(()) + fn pin_id(&self) -> u8 { + self.i } - #[inline(always)] - fn set_low(&mut self) -> Result<(), Self::Error> { - unsafe { (*self.port).set_low(self.i) } - Ok(()) - } -} - -impl InputPin for Pin> { - #[inline(always)] - fn is_high(&mut self) -> Result { - self.is_low().map(|v| !v) - } - - #[inline(always)] - fn is_low(&mut self) -> Result { - Ok(unsafe { (*self.port).is_low(self.i) }) - } -} - -impl embedded_hal::digital::ErrorType for Pin> { - type Error = Infallible; -} - -impl InputPin for Pin> { - #[inline(always)] - fn is_high(&mut self) -> Result { - self.is_low().map(|v| !v) - } - - #[inline(always)] - fn is_low(&mut self) -> Result { - Ok(unsafe { (*self.port).is_low(self.i) }) + fn port_id(&self) -> u8 { + self.p } } @@ -194,7 +290,7 @@ gpio_trait!(gpiof); gpio_trait!(gpioc); macro_rules! gpio { - ([$($GPIOX:ident, $gpiox:ident, $gpioxenr:ident, $PXx:ident, $gate:meta => [ + ([$($GPIOX:ident, $gpiox:ident, $gpioxenr:ident, $PXx:ident, $PCH:literal, $gate:meta => [ $($PXi:ident: ($pxi:ident, $i:expr, $MODE:ty),)+ ]),+]) => { $( @@ -202,11 +298,10 @@ macro_rules! gpio { #[cfg($gate)] pub mod $gpiox { use core::marker::PhantomData; - use core::convert::Infallible; - use embedded_hal::digital::{InputPin, OutputPin, StatefulOutputPin}; use crate::{ - rcc::Rcc, + rcc::{Enable, Reset}, + pac::RCC, pac::$GPIOX }; @@ -227,8 +322,21 @@ macro_rules! gpio { impl GpioExt for $GPIOX { type Parts = Parts; - fn split(self, rcc: &mut Rcc) -> Parts { - rcc.regs.iopenr.modify(|_, w| w.$gpioxenr().set_bit()); + fn split(self) -> Parts { + let rcc = unsafe { &(*RCC::ptr()) }; + $GPIOX::enable(rcc); + $GPIOX::reset(rcc); + + Parts { + $( + $pxi: $PXi { _mode: PhantomData }, + )+ + } + } + + unsafe fn split_without_reset(self) -> Parts { + let rcc = unsafe { &(*RCC::ptr()) }; + $GPIOX::enable(rcc); Parts { $( @@ -579,6 +687,30 @@ macro_rules! gpio { } impl $PXi> { + pub fn is_set_high(&mut self) -> bool { + !self.is_set_low() + } + + pub fn is_set_low(&mut self) -> bool { + unsafe { (*$GPIOX::ptr()).is_set_low($i) } + } + + pub fn set_high(&mut self) { + unsafe { (*$GPIOX::ptr()).set_high($i) }; + } + + fn set_low(&mut self) { + unsafe { (*$GPIOX::ptr()).set_low($i) }; + } + + fn is_high(&mut self) -> bool { + !self.is_low() + } + + fn is_low(&mut self) -> bool { + unsafe { (*$GPIOX::ptr()).is_low($i) } + } + /// Erases the pin number from the type /// /// This is useful when you want to collect the pins into an array where you @@ -586,47 +718,22 @@ macro_rules! gpio { pub fn downgrade(self) -> Pin> { Pin { i: $i, + p: $PCH, port: $GPIOX::ptr() as *const dyn GpioRegExt, _mode: self._mode, } } } - impl embedded_hal::digital::ErrorType for $PXi> { - type Error = Infallible; - } - - impl StatefulOutputPin for $PXi> { - fn is_set_high(&mut self) -> Result { - self.is_set_low().map(|v| !v) - } - - fn is_set_low(&mut self) -> Result { - Ok(unsafe { (*$GPIOX::ptr()).is_set_low($i) }) - } - } - - impl OutputPin for $PXi> { - fn set_high(&mut self) -> Result<(), Self::Error> { - Ok(unsafe { (*$GPIOX::ptr()).set_high($i) }) - } - - fn set_low(&mut self) -> Result<(), Self::Error> { - Ok(unsafe { (*$GPIOX::ptr()).set_low($i) }) - } - } - - impl InputPin for $PXi> { - fn is_high(&mut self) -> Result { - self.is_low().map(|v| !v) + impl $PXi> { + pub fn is_high(&mut self) -> bool { + !self.is_low() } - fn is_low(&mut self) -> Result { - Ok(unsafe { (*$GPIOX::ptr()).is_low($i) }) + pub fn is_low(&mut self) -> bool { + unsafe { (*$GPIOX::ptr()).is_low($i) } } - } - impl $PXi> { /// Erases the pin number from the type /// /// This is useful when you want to collect the pins into an array where you @@ -634,25 +741,13 @@ macro_rules! gpio { pub fn downgrade(self) -> Pin> { Pin { i: $i, + p: $PCH, port: $GPIOX::ptr() as *const dyn GpioRegExt, _mode: self._mode, } } } - impl embedded_hal::digital::ErrorType for $PXi> { - type Error = Infallible; - } - - impl InputPin for $PXi> { - fn is_high(&mut self) -> Result { - self.is_low().map(|v| !v) - } - - fn is_low(&mut self) -> Result { - Ok(unsafe { (*$GPIOX::ptr()).is_low($i) }) - } - } )+ } )+ @@ -660,7 +755,8 @@ macro_rules! gpio { } gpio!([ - GPIOA, gpioa, gpioaen, PA, any( + // BUGBUG: py32f002b only has 8 pins? + GPIOA, gpioa, gpioaen, PA, b'A', any( feature = "device-selected" ) => [ PA0: (pa0, 0, Input), @@ -680,7 +776,7 @@ gpio!([ PA14: (pa14, 14, Input), PA15: (pa15, 15, Input), ], - GPIOB, gpiob, gpioben, PB, any( + GPIOB, gpiob, gpioben, PB, b'B', any( feature = "device-selected" ) => [ PB0: (pb0, 0, Input), @@ -693,13 +789,13 @@ gpio!([ PB7: (pb7, 7, Input), PB8: (pb8, 8, Input), ], - GPIOC, gpioc, gpiocen, PC, any( + GPIOC, gpioc, gpiocen, PC, b'C', any( feature = "py32f002b" ) => [ PC0: (pf0, 0, Input), PC1: (pf1, 1, Input), ], - GPIOF, gpiof, gpiofen, PF, any( + GPIOF, gpiof, gpiofen, PF, b'F', any( feature = "py32f030", feature = "py32f003", feature = "py32f002a" diff --git a/src/gpio/hal_02.rs b/src/gpio/hal_02.rs new file mode 100644 index 0000000..54baa8a --- /dev/null +++ b/src/gpio/hal_02.rs @@ -0,0 +1,214 @@ +use super::*; +use embedded_hal_02::digital::v2::{InputPin, OutputPin, StatefulOutputPin, ToggleableOutputPin}; + +// Pin + +impl OutputPin for Pin { + type Error = PinModeError; + fn set_high(&mut self) -> Result<(), Self::Error> { + if self.mode.is_output() { + self._set_state(PinState::High); + Ok(()) + } else { + Err(PinModeError::IncorrectMode) + } + } + fn set_low(&mut self) -> Result<(), Self::Error> { + if self.mode.is_output() { + self._set_state(PinState::Low); + Ok(()) + } else { + Err(PinModeError::IncorrectMode) + } + } +} + +impl InputPin for Pin { + type Error = PinModeError; + fn is_high(&self) -> Result { + self.is_low().map(|b| !b) + } + fn is_low(&self) -> Result { + if self.mode.is_input() { + Ok(self._is_low()) + } else { + Err(PinModeError::IncorrectMode) + } + } +} + +impl OutputPin for Pin> { + type Error = Infallible; + #[inline] + fn set_high(&mut self) -> Result<(), Self::Error> { + self.set_high(); + Ok(()) + } + #[inline] + fn set_low(&mut self) -> Result<(), Self::Error> { + self.set_low(); + Ok(()) + } +} + +impl StatefulOutputPin for Pin> { + #[inline] + fn is_set_high(&self) -> Result { + Ok(self.is_set_high()) + } + #[inline] + fn is_set_low(&self) -> Result { + Ok(self.is_set_low()) + } +} + +impl ToggleableOutputPin for Pin> { + type Error = Infallible; + + #[inline(always)] + fn toggle(&mut self) -> Result<(), Self::Error> { + self.toggle(); + Ok(()) + } +} + +impl InputPin for Pin> { + type Error = Infallible; + #[inline] + fn is_high(&self) -> Result { + Ok(self.is_high()) + } + + #[inline] + fn is_low(&self) -> Result { + Ok(self.is_low()) + } +} + +impl InputPin for Pin> { + type Error = Infallible; + #[inline] + fn is_high(&self) -> Result { + Ok(self.is_high()) + } + + #[inline] + fn is_low(&self) -> Result { + Ok(self.is_low()) + } +} + +// PartiallyErasedPin + +impl OutputPin for PartiallyErasedPin> { + type Error = Infallible; + + #[inline(always)] + fn set_high(&mut self) -> Result<(), Self::Error> { + self.set_high(); + Ok(()) + } + + #[inline(always)] + fn set_low(&mut self) -> Result<(), Self::Error> { + self.set_low(); + Ok(()) + } +} + +impl StatefulOutputPin for PartiallyErasedPin> { + #[inline(always)] + fn is_set_high(&self) -> Result { + Ok(self.is_set_high()) + } + + #[inline(always)] + fn is_set_low(&self) -> Result { + Ok(self.is_set_low()) + } +} + +impl ToggleableOutputPin for PartiallyErasedPin> { + type Error = Infallible; + + #[inline(always)] + fn toggle(&mut self) -> Result<(), Self::Error> { + self.toggle(); + Ok(()) + } +} + +impl InputPin for PartiallyErasedPin> { + type Error = Infallible; + + #[inline(always)] + fn is_high(&self) -> Result { + Ok(self.is_high()) + } + + #[inline(always)] + fn is_low(&self) -> Result { + Ok(self.is_low()) + } +} + +impl InputPin for PartiallyErasedPin> { + type Error = Infallible; + + #[inline(always)] + fn is_high(&self) -> Result { + Ok(self.is_high()) + } + + #[inline(always)] + fn is_low(&self) -> Result { + Ok(self.is_low()) + } +} + +// ErasedPin + +impl OutputPin for ErasedPin> { + type Error = Infallible; + fn set_high(&mut self) -> Result<(), Infallible> { + self.set_high(); + Ok(()) + } + + fn set_low(&mut self) -> Result<(), Infallible> { + self.set_low(); + Ok(()) + } +} + +impl StatefulOutputPin for ErasedPin> { + fn is_set_high(&self) -> Result { + Ok(self.is_set_high()) + } + + fn is_set_low(&self) -> Result { + Ok(self.is_set_low()) + } +} + +impl InputPin for ErasedPin> { + type Error = Infallible; + fn is_high(&self) -> Result { + Ok(self.is_high()) + } + + fn is_low(&self) -> Result { + Ok(self.is_low()) + } +} + +impl InputPin for ErasedPin> { + type Error = Infallible; + fn is_high(&self) -> Result { + Ok(self.is_high()) + } + + fn is_low(&self) -> Result { + Ok(self.is_low()) + } +} diff --git a/src/gpio/hal_1.rs b/src/gpio/hal_1.rs new file mode 100644 index 0000000..6c3344d --- /dev/null +++ b/src/gpio/hal_1.rs @@ -0,0 +1,175 @@ +use core::convert::Infallible; + +use super::{Input, OpenDrain, Output, Pin}; + +//pub use embedded_hal::digital::PinState; +use embedded_hal::digital::{ErrorType, InputPin, OutputPin, StatefulOutputPin}; + +// fn into_state(state: PinState) -> super::PinState { +// match state { +// PinState::Low => super::PinState::Low, +// PinState::High => super::PinState::High, +// } +// } + +// Implementations for `Pin` +impl ErrorType for Pin> { + type Error = Infallible; +} +impl ErrorType for Pin> { + type Error = Infallible; +} + +impl StatefulOutputPin for Pin> { + #[inline(always)] + fn is_set_high(&mut self) -> Result { + self.is_set_low().map(|v| !v) + } + + #[inline(always)] + fn is_set_low(&mut self) -> Result { + Ok(unsafe { (*self.port).is_set_low(self.i) }) + } +} + +impl OutputPin for Pin> { + #[inline(always)] + fn set_high(&mut self) -> Result<(), Self::Error> { + unsafe { (*self.port).set_high(self.i) }; + Ok(()) + } + + #[inline(always)] + fn set_low(&mut self) -> Result<(), Self::Error> { + unsafe { (*self.port).set_low(self.i) } + Ok(()) + } +} + +impl InputPin for Pin> { + #[inline(always)] + fn is_high(&mut self) -> Result { + self.is_low().map(|v| !v) + } + + #[inline(always)] + fn is_low(&mut self) -> Result { + Ok(unsafe { (*self.port).is_low(self.i) }) + } +} + +impl InputPin for Pin> { + #[inline(always)] + fn is_high(&mut self) -> Result { + self.is_low().map(|v| !v) + } + + #[inline(always)] + fn is_low(&mut self) -> Result { + Ok(unsafe { (*self.port).is_low(self.i) }) + } +} + +// // PartiallyErasedPin + +// impl ErrorType for PartiallyErasedPin { +// type Error = Infallible; +// } + +// impl OutputPin for PartiallyErasedPin> { +// #[inline(always)] +// fn set_high(&mut self) -> Result<(), Self::Error> { +// self.set_high(); +// Ok(()) +// } + +// #[inline(always)] +// fn set_low(&mut self) -> Result<(), Self::Error> { +// self.set_low(); +// Ok(()) +// } +// } + +// impl StatefulOutputPin for PartiallyErasedPin> { +// #[inline(always)] +// fn is_set_high(&mut self) -> Result { +// Ok((*self).is_set_high()) +// } + +// #[inline(always)] +// fn is_set_low(&mut self) -> Result { +// Ok((*self).is_set_low()) +// } +// } + +// impl InputPin for PartiallyErasedPin> { +// #[inline(always)] +// fn is_high(&mut self) -> Result { +// Ok((*self).is_high()) +// } + +// #[inline(always)] +// fn is_low(&mut self) -> Result { +// Ok((*self).is_low()) +// } +// } + +// impl InputPin for PartiallyErasedPin> { +// #[inline(always)] +// fn is_high(&mut self) -> Result { +// Ok((*self).is_high()) +// } + +// #[inline(always)] +// fn is_low(&mut self) -> Result { +// Ok((*self).is_low()) +// } +// } + +// // ErasedPin + +// impl ErrorType for ErasedPin { +// type Error = core::convert::Infallible; +// } + +// impl OutputPin for ErasedPin> { +// fn set_high(&mut self) -> Result<(), Infallible> { +// self.set_high(); +// Ok(()) +// } + +// fn set_low(&mut self) -> Result<(), Infallible> { +// self.set_low(); +// Ok(()) +// } +// } + +// impl StatefulOutputPin for ErasedPin> { +// fn is_set_high(&mut self) -> Result { +// Ok((*self).is_set_high()) +// } + +// fn is_set_low(&mut self) -> Result { +// Ok((*self).is_set_low()) +// } +// } + +// impl InputPin for ErasedPin> { +// fn is_high(&mut self) -> Result { +// Ok((*self).is_high()) +// } + +// fn is_low(&mut self) -> Result { +// Ok((*self).is_low()) +// } +// } + +// impl InputPin for ErasedPin> { +// fn is_high(&mut self) -> Result { +// Ok((*self).is_high()) +// } + +// fn is_low(&mut self) -> Result { +// Ok((*self).is_low()) +// } +// } diff --git a/src/i2c.rs b/src/i2c.rs index ba4c5f1..1ea4c82 100644 --- a/src/i2c.rs +++ b/src/i2c.rs @@ -1,6 +1,6 @@ use core::ops::Deref; -use embedded_hal::blocking::i2c::{Read, Write, WriteRead}; +use embedded_hal_02::blocking::i2c::{Read, Write, WriteRead}; use crate::{ gpio::*, diff --git a/src/lib.rs b/src/lib.rs index 6714e31..a94347c 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -13,18 +13,20 @@ pub use py32f0::py32f003 as pac; #[cfg(feature = "py32f030")] pub use py32f0::py32f030 as pac; -//#[cfg(feature = "device-selected")] -//pub mod adc; #[cfg(feature = "device-selected")] +pub mod adc; +#[cfg(feature = "device-selected")] +pub mod delay; +#[cfg(all(feature = "device-selected", feature = "with-dma"))] pub mod dma; #[cfg(feature = "device-selected")] pub mod gpio; -//#[cfg(feature = "device-selected")] -//pub mod i2c; +#[cfg(feature = "device-selected")] +pub mod i2c; #[cfg(feature = "device-selected")] pub mod prelude; -//#[cfg(feature = "device-selected")] -//pub mod pwm; +#[cfg(feature = "device-selected")] +pub mod pwm; #[cfg(feature = "device-selected")] pub mod rcc; #[cfg(feature = "device-selected")] @@ -33,7 +35,12 @@ pub mod serial; pub mod spi; #[cfg(feature = "device-selected")] pub mod time; -//#[cfg(feature = "device-selected")] -//pub mod timers; -//#[cfg(feature = "device-selected")] -//pub mod watchdog; +#[cfg(feature = "device-selected")] +pub mod timers; +#[cfg(feature = "device-selected")] +pub mod watchdog; + +mod sealed { + pub trait Sealed {} +} +use sealed::Sealed; diff --git a/src/prelude.rs b/src/prelude.rs index 58df03c..6d11561 100644 --- a/src/prelude.rs +++ b/src/prelude.rs @@ -1,13 +1,15 @@ -// TODO for some reason, watchdog isn't in the embedded_hal prelude -//pub use embedded_hal::watchdog::Watchdog as _py32f0xx_hal_embedded_hal_watchdog_Watchdog; -//pub use embedded_hal::watchdog::WatchdogEnable as _py32f0xx_hal_embedded_hal_watchdog_WatchdogEnable; - -//pub use embedded_hal::adc::OneShot as _embedded_hal_adc_OneShot; - -pub use embedded_hal::digital::InputPin as _embedded_hal_gpio_InputPin; -pub use embedded_hal::digital::OutputPin as _embedded_hal_gpio_OutputPin; -pub use embedded_hal::digital::StatefulOutputPin as _embedded_hal_gpio_StatefulOutputPin; - +#[cfg(feature = "with-dma")] +pub use crate::dma::CircReadDma as _py32f0xx_hal_dma_CircReadDma; +#[cfg(feature = "with-dma")] +pub use crate::dma::DmaExt as _py32f0xx_hal_dma_DmaExt; +#[cfg(feature = "with-dma")] +pub use crate::dma::ReadDma as _py32f0xx_hal_dma_ReadDma; +#[cfg(feature = "with-dma")] +pub use crate::dma::ReadWriteDma as _py32f0xx_hal_dma_ReadWriteDma; +#[cfg(feature = "with-dma")] +pub use crate::dma::WriteDma as _py32f0xx_hal_dma_WriteDma; pub use crate::gpio::GpioExt as _py32f0xx_hal_gpio_GpioExt; pub use crate::rcc::RccExt as _py32f0xx_hal_rcc_RccExt; +pub use crate::serial::SerialExt as _; +pub use crate::spi::SpiExt as _; pub use crate::time::U32Ext as _py32f0xx_hal_time_U32Ext; diff --git a/src/pwm.rs b/src/pwm.rs index 6c6258b..ca63c73 100644 --- a/src/pwm.rs +++ b/src/pwm.rs @@ -4,7 +4,7 @@ use core::{marker::PhantomData, mem::MaybeUninit}; use crate::rcc::Rcc; use crate::time::Hertz; -use embedded_hal as hal; +use embedded_hal_02 as hal; pub trait Pins { const C1: bool = false; @@ -715,7 +715,7 @@ macro_rules! pwm_1_channel { rcc.regs.$apbrstr.modify(|_, w| w.$timXrst().clear_bit()); if PINS::C1 { - tim.ccmr1_output().modify(|_, w| unsafe { w.oc1pe().set_bit().oc1m().bits(6) }); + tim.ccmr1_output().modify(|_, w| w.oc1pe().set_bit().oc1m().bits(6)); } // If pclk is prescaled from hclk, the frequency fed into the timers is doubled diff --git a/src/rcc.rs b/src/rcc.rs index 6ad663e..0ca8da0 100644 --- a/src/rcc.rs +++ b/src/rcc.rs @@ -1,12 +1,15 @@ +use crate::pac::rcc; use crate::pac::rcc::{ cfgr::{MCOPRE_A, MCOSEL_A}, cr::HSIDIV_A, icscr::HSI_FS_A, }; -use crate::pac::RCC; +use crate::pac::{PWR, RCC}; use crate::time::Hertz; +mod enable; + /// Extension trait that sets up the `RCC` peripheral pub trait RccExt { /// Configure the clocks of the RCC peripheral @@ -39,6 +42,22 @@ impl Rcc { } } +/// AMBA High-performance Bus (AHB) registers +#[non_exhaustive] +pub struct AHB; + +/// Advanced Peripheral Bus (APB) registers +#[non_exhaustive] +pub struct APB; + +impl APB { + /// Set power interface clock (PWREN) bit in RCC_APB1ENR + pub fn set_pwren() { + let rcc = unsafe { &*RCC::ptr() }; + PWR::enable(rcc); + } +} + /// MCO source select #[derive(Clone, Copy)] pub enum MCOSrc { @@ -301,6 +320,109 @@ mod inner { } } +/// Frequency on bus that peripheral is connected in +pub trait BusClock { + /// Calculates frequency depending on `Clock` state + fn clock(clocks: &Clocks) -> Hertz; +} + +/// Frequency on bus that timer is connected in +pub trait BusTimerClock { + /// Calculates base frequency of timer depending on `Clock` state + fn timer_clock(clocks: &Clocks) -> Hertz; +} + +impl BusClock for T +where + T: RccBus, + T::Bus: BusClock, +{ + fn clock(clocks: &Clocks) -> Hertz { + T::Bus::clock(clocks) + } +} + +impl BusTimerClock for T +where + T: RccBus, + T::Bus: BusTimerClock, +{ + fn timer_clock(clocks: &Clocks) -> Hertz { + T::Bus::timer_clock(clocks) + } +} + +impl BusClock for AHB { + fn clock(clocks: &Clocks) -> Hertz { + clocks.hclk + } +} + +impl BusClock for APB { + fn clock(clocks: &Clocks) -> Hertz { + clocks.pclk + } +} + +impl BusTimerClock for APB { + fn timer_clock(clocks: &Clocks) -> Hertz { + clocks.pclk_tim() + } +} + +/// Bus associated to peripheral +pub trait RccBus: crate::Sealed { + /// Bus type; + type Bus; +} + +/// Enable/disable peripheral +pub trait Enable: RccBus { + fn enable(rcc: &rcc::RegisterBlock); + fn disable(rcc: &rcc::RegisterBlock); +} +/// Reset peripheral +pub trait Reset: RccBus { + fn reset(rcc: &rcc::RegisterBlock); +} + +/// Frozen clock frequencies +/// +/// The existence of this value indicates that the clock configuration can no longer be changed +#[derive(Clone, Copy)] +pub struct Clocks { + hclk: Hertz, + pclk: Hertz, + sysclk: Hertz, + ppre: u8, +} + +impl Clocks { + /// Returns the frequency of the AHB + pub const fn hclk(&self) -> Hertz { + self.hclk + } + + /// Returns the system (core) frequency + pub const fn sysclk(&self) -> Hertz { + self.sysclk + } + + /// Returns the frequency of the APB + pub const fn pclk(&self) -> Hertz { + self.pclk + } + + /// Returns the frequency of the APB Timers + pub const fn pclk_tim(&self) -> Hertz { + Hertz(self.pclk.0 * if self.ppre() == 1 { 1 } else { 2 }) + } + + pub(crate) const fn ppre(&self) -> u8 { + self.ppre + } +} + use self::inner::SysClkSource; pub struct CFGR { @@ -463,35 +585,9 @@ impl CFGR { hclk: Hertz(hclk), pclk: Hertz(pclk), sysclk: Hertz(sysclk), + ppre, }, regs: self.rcc, } } } - -/// Frozen clock frequencies -/// -/// The existence of this value indicates that the clock configuration can no longer be changed -#[derive(Clone, Copy)] -pub struct Clocks { - hclk: Hertz, - pclk: Hertz, - sysclk: Hertz, -} - -impl Clocks { - /// Returns the frequency of the AHB - pub fn hclk(&self) -> Hertz { - self.hclk - } - - /// Returns the frequency of the APB - pub fn pclk(&self) -> Hertz { - self.pclk - } - - /// Returns the system (core) frequency - pub fn sysclk(&self) -> Hertz { - self.sysclk - } -} diff --git a/src/rcc/enable.rs b/src/rcc/enable.rs new file mode 100644 index 0000000..d0c326a --- /dev/null +++ b/src/rcc/enable.rs @@ -0,0 +1,98 @@ +use super::*; + +macro_rules! bus { + ($($PER:ident => ($apbX:ty, $enr:tt, $rstr:tt, $bit:literal),)+) => { + $( + impl crate::Sealed for crate::pac::$PER {} + + impl RccBus for crate::pac::$PER { + type Bus = $apbX; + } + impl Enable for crate::pac::$PER { + #[inline(always)] + fn enable(rcc: &rcc::RegisterBlock) { + unsafe { + rcc.$enr.modify(|r,w| w.bits(r.bits() | (1 << $bit))); + } + } + #[inline(always)] + fn disable(rcc: &rcc::RegisterBlock) { + unsafe { + rcc.$enr.modify(|r,w| w.bits(r.bits() & !(1 << $bit))); + } + } + } + impl Reset for crate::pac::$PER { + #[inline(always)] + fn reset(rcc: &rcc::RegisterBlock) { + unsafe { + rcc.$rstr.modify(|r,w| w.bits(r.bits() | (1 << $bit))); + rcc.$rstr.modify(|r,w| w.bits(r.bits() & !(1 << $bit))); + } + } + } + )+ + } +} + +bus! { + ADC => (APB, apbenr2, apbrstr2, 20), + CRC => (AHB, ahbenr, ahbrstr, 12), + DBG => (APB, apbenr1, apbrstr1, 27), + GPIOA => (APB, iopenr, ioprstr, 0), + GPIOB => (APB, iopenr, ioprstr, 1), + I2C => (APB, apbenr1, apbrstr1, 21), + PWR => (APB, apbenr1, apbrstr1, 28), + SPI1 => (APB, apbenr2, apbrstr2, 12), + SYSCFG => (APB, apbenr2, apbrstr2, 0), + TIM1 => (APB, apbenr2, apbrstr2, 11), + USART1 => (APB, apbenr2, apbrstr2, 14), +} + +#[cfg(any(feature = "py32f003", feature = "py32f030"))] +bus! { + USART2 => (APB, apbenr1, apbrstr1, 17), + DMA => (AHB, ahbenr, ahbrstr, 0), + WWDG => (APB, apbenr1, apbrstr1, 11), +} + +#[cfg(any(feature = "py32f030"))] +bus! { + SPI2 => (APB, apbenr1, apbrstr1, 14), +} + +#[cfg(any(feature = "py32f002a", feature = "py32f003", feature = "py32f030"))] +bus! { + GPIOF => (APB, iopenr, ioprstr, 5), + LPTIM => (APB, apbenr1, apbrstr1, 31), +} + +#[cfg(any(feature = "py32f002b"))] +bus! { + LPTIM1 => (APB, apbenr1, apbrstr1, 31), +} + +#[cfg(any(feature = "py32f030"))] +bus! { + LED => (APB, apbenr2, apbrstr2, 23), +} + +#[cfg(any(feature = "py32f003", feature = "py32f030"))] +bus! { + TIM3 => (APB, apbenr1, apbrstr1, 1), +} + +#[cfg(any(feature = "py32f002b", feature = "py32f003", feature = "py32f030"))] +bus! { + TIM14 => (APB, apbenr2, apbrstr2, 15), +} + +#[cfg(any(feature = "py32f002a", feature = "py32f003", feature = "py32f030"))] +bus! { + TIM16 => (APB, apbenr2, apbrstr2, 17), +} + +#[cfg(any(feature = "py32f003", feature = "py32f030"))] +bus! { + TIM17 => (APB, apbenr2, apbrstr2, 18), +} diff --git a/src/serial.rs b/src/serial.rs index 3c01d3e..a99594d 100644 --- a/src/serial.rs +++ b/src/serial.rs @@ -16,21 +16,21 @@ //! //! use nb::block; //! -//! cortex_m::interrupt::free(|cs| { -//! let rcc = p.RCC.configure().sysclk(24.mhz()).freeze(); +//! let rcc = p.RCC.configure().sysclk(24.mhz()).freeze(); //! -//! let gpioa = p.GPIOA.split(&mut rcc); +//! let gpiob = p.GPIOB.split(&mut rcc); //! -//! let tx = gpioa.pa9.into_alternate_af1(cs); -//! let rx = gpioa.pa10.into_alternate_af1(cs); +//! // USART1 on Pins B6 and B7 +//! let tx = gpiob.pb6.into_alternate_af0(); +//! let rx = gpiob.pb7.into_alternate_af0(); //! -//! let mut serial = Serial::usart1(p.USART1, (tx, rx), 115_200.bps(), &mut rcc); +//! // Create an interface struct for USART1 with 115200 Baud +//! let mut serial = Serial::new(p.USART1, (tx, rx), 115_200.bps(), &rcc.clocks); //! -//! loop { -//! let received = block!(serial.read()).unwrap(); -//! block!(serial.write(received)).ok(); -//! } -//! }); +//! loop { +//! let received = block!(serial.read()).unwrap(); +//! block!(serial.write_u8(received)).ok(); +//! } //! ``` //! //! Hello World @@ -43,29 +43,34 @@ //! //! use nb::block; //! -//! cortex_m::interrupt::free(|cs| { -//! let rcc = p.RCC.configure().sysclk(24.mhz()).freeze(); +//! let rcc = p.RCC.configure().sysclk(24.mhz()).freeze(); //! -//! let gpioa = p.GPIOA.split(&mut rcc); +//! let gpiob = p.GPIOB.split(&mut rcc); //! -//! let tx = gpioa.pa9.into_alternate_af1(cs); +//! let tx = gpiob.pb6.into_alternate_af0(); //! -//! let mut serial = Serial::usart1tx(p.USART1, tx, 115_200.bps(), &mut rcc); +//! let mut serial = Serial::new(p.USART1, tx, 115_200.bps(), &rcc.clocks); //! -//! loop { -//! serial.write_str("Hello World!\r\n"); -//! } -//! }); +//! loop { +//! serial.write_str("Hello World!\r\n"); +//! } //! ``` -use core::{ - fmt::{Result, Write}, - ops::Deref, +use core::marker::PhantomData; +use core::ops::Deref; +use core::sync::atomic::{self, Ordering}; +use embedded_dma::{ReadBuffer, WriteBuffer}; + +#[cfg(feature = "with-dma")] +use crate::dma::{ + self, Ch, CircBuffer, DmaExt, PeriphMap, Receive, RxDma, Transfer, TransferPayload, Transmit, + TxDma, }; - use crate::gpio::{gpioa::*, gpiob::*}; use crate::gpio::{Alternate, AF1}; -use crate::{rcc::Rcc, time::Bps}; +use crate::pac::{self, RCC}; +use crate::rcc::{BusClock, Clocks, Enable, Reset}; +use crate::time::{Bps, U32Ext}; #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] use crate::gpio::{gpiof::*, AF0, AF8}; @@ -76,33 +81,8 @@ use crate::gpio::{AF3, AF4, AF9}; #[cfg(feature = "py32f002b")] use crate::gpio::AF3; -use core::marker::PhantomData; - -/// Serial error -#[non_exhaustive] -#[derive(Debug)] -pub enum Error { - /// Framing error - Framing, - /// Noise error - Noise, - /// RX buffer overrun - Overrun, - /// Parity check error - Parity, -} - -/// Interrupt event -pub enum Event { - /// New data has been received - Rxne, - /// New data can be sent - Txe, - /// Idle line state detected - Idle, - /// Transmission complete - Txc, -} +mod hal_02; +mod hal_1; pub trait TxPin {} pub trait RxPin {} @@ -206,394 +186,853 @@ impl_pins!( PB6, AF1, USART1, TxPin; ); -/// Serial abstraction -pub struct Serial { - usart: USART, - pins: (TXPIN, RXPIN), +pub trait SerialExt: Sized + Instance { + fn serial( + self, + pins: (TXPIN, RXPIN), + config: impl Into, + clocks: &Clocks, + ) -> Serial; + fn tx(self, tx_pin: TXPIN, config: impl Into, clocks: &Clocks) -> Tx; + fn rx(self, rx_pin: RXPIN, config: impl Into, clocks: &Clocks) -> Rx; } -// Common register -type SerialRegisterBlock = crate::pac::usart1::RegisterBlock; - -/// Serial receiver -pub struct Rx { - usart: *const SerialRegisterBlock, - _instance: PhantomData, +impl SerialExt for USART { + fn serial( + self, + pins: (TXPIN, RXPIN), + config: impl Into, + clocks: &Clocks, + ) -> Serial { + Serial::new(self, pins, config, clocks) + } + fn tx(self, tx_pin: TXPIN, config: impl Into, clocks: &Clocks) -> Tx { + Serial::_new(self, (tx_pin, ()), config, clocks).split().0 + } + fn rx(self, rx_pin: RXPIN, config: impl Into, clocks: &Clocks) -> Rx { + Serial::_new(self, ((), rx_pin), config, clocks).split().1 + } } -// NOTE(unsafe) Required to allow protected shared access in handlers -unsafe impl Send for Rx {} +use crate::pac::usart1 as uart_base; -/// Serial transmitter -pub struct Tx { - usart: *const SerialRegisterBlock, - _instance: PhantomData, +pub trait Instance: + crate::Sealed + Deref + Enable + Reset + BusClock +{ + #[doc(hidden)] + fn ptr() -> *const uart_base::RegisterBlock; } -// NOTE(unsafe) Required to allow protected shared access in handlers -unsafe impl Send for Tx {} - -macro_rules! usart { - ($($USART:ident: ($usart:ident, $usarttx:ident, $usartrx:ident, $usartXen:ident, $apbenr:ident),)+) => { +macro_rules! inst { + ($($USARTX:ty;)+) => { $( - use crate::pac::$USART; - impl Serial<$USART, TXPIN, RXPIN> - where - TXPIN: TxPin<$USART>, - RXPIN: RxPin<$USART>, - { - /// Creates a new serial instance - pub fn $usart(usart: $USART, pins: (TXPIN, RXPIN), baud_rate: Bps, rcc: &mut Rcc) -> Self - { - let mut serial = Serial { usart, pins }; - serial.configure(baud_rate, rcc); - // Enable transmission and receiving - serial.usart.cr1.modify(|_, w| w.te().set_bit().re().set_bit().ue().set_bit()); - serial + impl Instance for $USARTX { + fn ptr() -> *const uart_base::RegisterBlock { + <$USARTX>::ptr() } } + )+ + }; +} - impl Serial<$USART, TXPIN, ()> - where - TXPIN: TxPin<$USART>, - { - /// Creates a new tx-only serial instance - pub fn $usarttx(usart: $USART, txpin: TXPIN, baud_rate: Bps, rcc: &mut Rcc) -> Self - { - let rxpin = (); - let mut serial = Serial { usart, pins: (txpin, rxpin) }; - serial.configure(baud_rate, rcc); - // Enable transmission - serial.usart.cr1.modify(|_, w| w.te().set_bit().ue().set_bit()); - serial - } - } +#[cfg(any( + feature = "py32f002a", + feature = "py32f002b", + feature = "py32f003", + feature = "py32f030", +))] +inst! { + pac::USART1; +} - impl Serial<$USART, (), RXPIN> - where - RXPIN: RxPin<$USART>, - { - /// Creates a new rx-only serial instance - pub fn $usartrx(usart: $USART, rxpin: RXPIN, baud_rate: Bps, rcc: &mut Rcc) -> Self - { - let txpin = (); - let mut serial = Serial { usart, pins: (txpin, rxpin) }; - serial.configure(baud_rate, rcc); - // Enable receiving - serial.usart.cr1.modify(|_, w| w.re().set_bit().ue().set_bit()); - serial - } - } +#[cfg(any(feature = "py32f003", feature = "py32f030",))] +inst! { + pac::USART2; +} - impl Serial<$USART, TXPIN, RXPIN> { - fn configure(&mut self, baud_rate: Bps, rcc: &mut Rcc) { - // Enable clock for USART - rcc.regs.$apbenr.modify(|_, w| w.$usartXen().set_bit()); +/// Serial error +#[derive(Debug)] +#[non_exhaustive] +pub enum Error { + /// The peripheral receive buffer was overrun. + Overrun, + /// Received data does not conform to the peripheral configuration. + /// Can be caused by a misconfigured device on either end of the serial line. + FrameFormat, + /// Parity check failed. + Parity, + /// Serial line is too noisy to read valid data. + Noise, + /// A different error occurred. The original error may contain more information. + Other, +} - // Calculate correct baudrate divisor on the fly - let brr = rcc.clocks.pclk().0 / baud_rate.0; - self.usart.brr.write(|w| unsafe { w.bits(brr) }); +pub enum WordLength { + /// When parity is enabled, a word has 7 data bits + 1 parity bit, + /// otherwise 8 data bits. + Bits8, + /// When parity is enabled, a word has 8 data bits + 1 parity bit, + /// otherwise 9 data bits. + Bits9, +} - // Reset other registers to disable advanced USART features - self.usart.cr2.reset(); - self.usart.cr3.reset(); - } +pub enum Parity { + ParityNone, + ParityEven, + ParityOdd, +} - /// Starts listening for an interrupt event - pub fn listen(&mut self, event: Event) { - match event { - Event::Rxne => { - self.usart.cr1.modify(|_, w| w.rxneie().set_bit()) - }, - Event::Txe => { - self.usart.cr1.modify(|_, w| w.txeie().set_bit()) - }, - Event::Idle => { - self.usart.cr1.modify(|_, w| w.idleie().set_bit()) - }, - Event::Txc => { - self.usart.cr1.modify(|_, w| w.tcie().set_bit()) - }, - } - } +pub enum StopBits { + /// 1 stop bit + STOP1, + /// 2 stop bits + STOP2, +} - /// Stop listening for an interrupt event - pub fn unlisten(&mut self, event: Event) { - match event { - Event::Rxne => { - self.usart.cr1.modify(|_, w| w.rxneie().clear_bit()) - }, - Event::Txe => { - self.usart.cr1.modify(|_, w| w.txeie().clear_bit()) - }, - Event::Idle => { - self.usart.cr1.modify(|_, w| w.idleie().clear_bit()) - }, - Event::Txc => { - self.usart.cr1.modify(|_, w| w.tcie().clear_bit()) - }, - } - } +pub struct Config { + pub baudrate: Bps, + pub wordlength: WordLength, + pub parity: Parity, + pub stopbits: StopBits, +} - /// Returns true if the line idle status is set - pub fn is_idle(&self) -> bool { - self.usart.sr.read().idle().bit_is_set() - } +impl Config { + pub fn baudrate(mut self, baudrate: Bps) -> Self { + self.baudrate = baudrate; + self + } - /// Returns true if the tx register is empty - pub fn is_txe(&self) -> bool { - self.usart.sr.read().txe().bit_is_set() - } + pub fn wordlength(mut self, wordlength: WordLength) -> Self { + self.wordlength = wordlength; + self + } - /// Returns true if the rx register is not empty (and can be read) - pub fn is_rx_not_empty(&self) -> bool { - self.usart.sr.read().rxne().bit_is_set() - } + pub fn wordlength_8bits(mut self) -> Self { + self.wordlength = WordLength::Bits8; + self + } - /// Returns true if transmission is complete - pub fn is_tx_complete(&self) -> bool { - self.usart.sr.read().tc().bit_is_set() - } - } + pub fn wordlength_9bits(mut self) -> Self { + self.wordlength = WordLength::Bits9; + self + } - impl Tx<$USART> { + pub fn parity(mut self, parity: Parity) -> Self { + self.parity = parity; + self + } - /// Starts listening for TXE interrupt event - pub fn listen_txe(&mut self) { - unsafe { (*self.usart).cr1.modify(|_, w| w.txeie().set_bit()) } - } + pub fn parity_none(mut self) -> Self { + self.parity = Parity::ParityNone; + self + } - /// Stop listening for TXE interrupt event - pub fn unlisten_txe(&mut self) { - unsafe { (*self.usart).cr1.modify(|_, w| w.txeie().clear_bit()) } - } + pub fn parity_even(mut self) -> Self { + self.parity = Parity::ParityEven; + self + } - /// Returns true if the rx register is not empty (and can be read) - pub fn is_txe(&self) -> bool { - unsafe { (*self.usart).sr.read().txe().bit_is_set() } - } + pub fn parity_odd(mut self) -> Self { + self.parity = Parity::ParityOdd; + self + } - /// Returns true if transmission is complete - pub fn is_tx_complete(&self) -> bool { - unsafe { (*self.usart).sr.read().tc().bit_is_set() } - } - } + pub fn stopbits(mut self, stopbits: StopBits) -> Self { + self.stopbits = stopbits; + self + } +} - impl Rx<$USART> { +impl Default for Config { + fn default() -> Config { + Config { + baudrate: 115_200_u32.bps(), + wordlength: WordLength::Bits8, + parity: Parity::ParityNone, + stopbits: StopBits::STOP1, + } + } +} - /// Starts listening for RXNE interrupt event - pub fn listen_rxne(&mut self) { - unsafe { (*self.usart).cr1.modify(|_, w| w.rxneie().set_bit()) } - } +impl From for Config { + fn from(baud: Bps) -> Self { + Config::default().baudrate(baud) + } +} - /// Stop listening for RXNE interrupt event - pub fn unlisten_rxne(&mut self) { - unsafe { (*self.usart).cr1.modify(|_, w| w.rxneie().clear_bit()) } - } +/// Serial abstraction +pub struct Serial { + pub tx: Tx, + pub rx: Rx, + #[allow(clippy::type_complexity)] + pub token: ReleaseToken, +} - /// Returns true if the rx register is not empty (and can be read) - pub fn is_rx_not_empty(&self) -> bool { - unsafe { (*self.usart).sr.read().rxne().bit_is_set() } - } +/// Serial transmitter +pub struct Tx { + _usart: PhantomData, +} - } +/// Serial receiver +pub struct Rx { + _usart: PhantomData, +} - )+ - } +/// Stores data for release +pub struct ReleaseToken { + usart: USART, + pins: PINS, } -#[cfg(any( - feature = "py32f002a", - feature = "py32f002b", - feature = "py32f003", - feature = "py32f030", -))] -usart! { - USART1: (usart1, usart1tx, usart1rx, usart1en, apbenr2), +impl Serial { + pub fn tx( + usart: USART, + tx_pin: TXPIN, + config: impl Into, + clocks: &Clocks, + ) -> Tx { + Self::_new(usart, (tx_pin, ()), config, clocks).split().0 + } } -#[cfg(any(feature = "py32f003", feature = "py32f030",))] -usart! { - USART2: (usart2, usart2tx, usart2rx,usart2en, apbenr1), +impl Serial { + pub fn rx( + usart: USART, + rx_pin: RXPIN, + config: impl Into, + clocks: &Clocks, + ) -> Rx { + Self::_new(usart, ((), rx_pin), config, clocks).split().1 + } } -use embedded_hal_nb::{serial, serial::ErrorKind, serial::Write as OtherWrite}; +impl Serial { + /// Configures the serial interface and creates the interface + /// struct. + /// + /// `Bps` is the baud rate of the interface. + /// + /// `Clocks` passes information about the current frequencies of + /// the clocks. The existence of the struct ensures that the + /// clock settings are fixed. + /// + /// The `serial` struct takes ownership over the `USARTX` device + /// registers and the specified `PINS` + pub fn new( + usart: USART, + pins: (TXPIN, RXPIN), + config: impl Into, + clocks: &Clocks, + ) -> Self { + Self::_new(usart, (pins.0, pins.1), config, clocks) + } -impl serial::Error for Error { - fn kind(&self) -> ErrorKind { - match self { - Error::Overrun => ErrorKind::Overrun, - Error::Framing => ErrorKind::FrameFormat, - Error::Parity => ErrorKind::Parity, - Error::Noise => ErrorKind::Noise, + fn _new( + usart: USART, + pins: (TXPIN, RXPIN), + config: impl Into, + clocks: &Clocks, + ) -> Self { + // Enable and reset USART + let rcc = unsafe { &(*RCC::ptr()) }; + USART::enable(rcc); + USART::reset(rcc); + + apply_config::(config.into(), clocks); + + let pins = (pins.0, pins.1); + + // UE: enable USART + // TE: enable transceiver + // RE: enable receiver + usart.cr1.modify(|_r, w| { + w.ue().enabled(); + w.te().enabled(); + w.re().enabled() + }); + + Serial { + tx: Tx { + _usart: PhantomData, + }, + rx: Rx { + _usart: PhantomData, + }, + token: ReleaseToken { usart, pins }, } } } -impl serial::ErrorType for Rx { - type Error = Error; -} +impl Serial { + /// Reconfigure the USART instance. + /// + /// If a transmission is currently in progress, this returns + /// [`nb::Error::WouldBlock`]. + pub fn reconfigure( + &mut self, + config: impl Into, + clocks: &Clocks, + ) -> nb::Result<(), Error> { + reconfigure(&mut self.tx, &mut self.rx, config, clocks) + } -impl embedded_hal_nb::serial::Read for Rx -where - USART: Deref, -{ - /// Tries to read a byte from the uart - fn read(&mut self) -> nb::Result { - read(self.usart) + /// Returns ownership of the borrowed register handles + /// + /// # Examples + /// + /// Basic usage: + /// + /// ``` + /// let mut serial = Serial::new(usart, (tx_pin, rx_pin), 9600.bps(), &clocks); + /// + /// // You can split the `Serial` + /// let Serial { tx, rx, token } = serial; + /// + /// // You can reunite the `Serial` back + /// let serial = Serial { tx, rx, token }; + /// + /// // Release `Serial` + /// let (usart, (tx_pin, rx_pin)) = serial.release(); + /// ``` + #[allow(clippy::type_complexity)] + pub fn release(self) -> (USART, (TXPIN, RXPIN)) { + (self.token.usart, self.token.pins) } -} -impl serial::ErrorType for Serial { - type Error = Error; + /// Separates the serial struct into separate channel objects for sending (Tx) and + /// receiving (Rx) + /// + /// If in the future it will be necessary to free up resources, + /// then you need to use a different method of separation: + /// + /// ``` + /// let Serial { tx, rx, token } = serial; + /// ``` + pub fn split(self) -> (Tx, Rx) { + (self.tx, self.rx) + } } -impl embedded_hal_nb::serial::Read for Serial -where - USART: Deref, - RXPIN: RxPin, -{ - /// Tries to read a byte from the uart - fn read(&mut self) -> nb::Result { - read(&*self.usart) - } +fn apply_config(config: Config, clocks: &Clocks) { + let usart = unsafe { &*USART::ptr() }; + + // Configure baud rate + let brr = USART::clock(clocks).0 / config.baudrate.0; + assert!(brr >= 16, "impossible baud rate"); + usart.brr.write(|w| unsafe { w.bits(brr) }); + + // Configure word + usart.cr1.modify(|_r, w| { + use crate::pac::usart1::cr1::M_A; + w.m().variant(match config.wordlength { + WordLength::Bits8 => M_A::M8, + WordLength::Bits9 => M_A::M9, + }); + use crate::pac::usart1::cr1::PS_A; + w.ps().variant(match config.parity { + Parity::ParityOdd => PS_A::Odd, + _ => PS_A::Even, + }); + w.pce().bit(!matches!(config.parity, Parity::ParityNone)); + w + }); + + // Configure stop bits + use crate::pac::usart1::cr2::STOP_A; + let stop_bits = match config.stopbits { + StopBits::STOP1 => STOP_A::Stop1, + StopBits::STOP2 => STOP_A::Stop2, + }; + usart.cr2.modify(|_r, w| w.stop().variant(stop_bits)); } -impl serial::ErrorType for Tx { - type Error = Error; +/// Reconfigure the USART instance. +/// +/// If a transmission is currently in progress, this returns +/// [`nb::Error::WouldBlock`]. +pub fn reconfigure( + tx: &mut Tx, + #[allow(unused_variables)] rx: &mut Rx, + config: impl Into, + clocks: &Clocks, +) -> nb::Result<(), Error> { + // if we're currently busy transmitting, we have to wait until that is + // over -- regarding reception, we assume that the caller -- with + // exclusive access to the Serial instance due to &mut self -- knows + // what they're doing. + tx.flush()?; + apply_config::(config.into(), clocks); + Ok(()) } -impl embedded_hal_nb::serial::Write for Tx -where - USART: Deref, -{ - /// Ensures that none of the previously written words are still buffered - fn flush(&mut self) -> nb::Result<(), Self::Error> { - flush(self.usart) +impl Tx { + /// Writes 9-bit words to the UART/USART + /// + /// If the UART/USART was configured with `WordLength::Bits9`, the 9 least significant bits will + /// be transmitted and the other 7 bits will be ignored. Otherwise, the 8 least significant bits + /// will be transmitted and the other 8 bits will be ignored. + pub fn write_u16(&mut self, word: u16) -> nb::Result<(), Error> { + let usart = unsafe { &*USART::ptr() }; + + if usart.sr.read().txe().bit_is_set() { + usart.dr().write(|w| w.dr().bits(word)); + Ok(()) + } else { + Err(nb::Error::WouldBlock) + } } - /// Tries to write a byte to the uart - /// Fails if the transmit buffer is full - fn write(&mut self, byte: u8) -> nb::Result<(), Self::Error> { - write(self.usart, byte) + pub fn write_u8(&mut self, word: u8) -> nb::Result<(), Error> { + self.write_u16(word as u16) } -} -impl embedded_hal_nb::serial::Write for Serial -where - USART: Deref, - TXPIN: TxPin, -{ - /// Ensures that none of the previously written words are still buffered - fn flush(&mut self) -> nb::Result<(), Self::Error> { - flush(&*self.usart) + pub fn bwrite_all_u16(&mut self, buffer: &[u16]) -> Result<(), Error> { + for &w in buffer { + nb::block!(self.write_u16(w))?; + } + Ok(()) } - /// Tries to write a byte to the uart - /// Fails if the transmit buffer is full - fn write(&mut self, byte: u8) -> nb::Result<(), Self::Error> { - write(&*self.usart, byte) + pub fn bwrite_all_u8(&mut self, buffer: &[u8]) -> Result<(), Error> { + for &w in buffer { + nb::block!(self.write_u8(w))?; + } + Ok(()) } -} -impl Serial -where - USART: Deref, -{ - /// Splits the UART Peripheral in a Tx and an Rx part - /// This is required for sending/receiving - pub fn split(self) -> (Tx, Rx) - where - TXPIN: TxPin, - RXPIN: RxPin, - { - ( - Tx { - usart: &*self.usart, - _instance: PhantomData, - }, - Rx { - usart: &*self.usart, - _instance: PhantomData, - }, - ) + pub fn flush(&mut self) -> nb::Result<(), Error> { + let usart = unsafe { &*USART::ptr() }; + + if usart.sr.read().tc().bit_is_set() { + Ok(()) + } else { + Err(nb::Error::WouldBlock) + } } - pub fn release(self) -> (USART, (TXPIN, RXPIN)) { - (self.usart, self.pins) + pub fn bflush(&mut self) -> Result<(), Error> { + nb::block!(self.flush()) + } + + /// Start listening for transmit interrupt event + pub fn listen(&mut self) { + unsafe { (*USART::ptr()).cr1.modify(|_, w| w.txeie().set_bit()) }; + } + + /// Stop listening for transmit interrupt event + pub fn unlisten(&mut self) { + unsafe { (*USART::ptr()).cr1.modify(|_, w| w.txeie().clear_bit()) }; + } + + /// Returns true if the tx register is empty (and can accept data) + pub fn is_tx_empty(&self) -> bool { + unsafe { (*USART::ptr()).sr.read().txe().bit_is_set() } + } + + /// Returns true if the transmission is complete, transmitter can be turned off safely + pub fn is_tx_complete(&self) -> bool { + unsafe { (*USART::ptr()).sr.read().tc().bit_is_set() } } } -impl Write for Tx -where - Tx: embedded_hal_nb::serial::Write, -{ - fn write_str(&mut self, s: &str) -> Result { - s.as_bytes() - .iter() - .try_for_each(|c| nb::block!(self.write(*c))) +impl core::fmt::Write for Tx { + fn write_str(&mut self, s: &str) -> core::fmt::Result { + s.bytes() + .try_for_each(|c| nb::block!(self.write_u8(c))) .map_err(|_| core::fmt::Error) } } -impl Write for Serial -where - USART: Deref, - TXPIN: TxPin, -{ - fn write_str(&mut self, s: &str) -> Result { - s.as_bytes() - .iter() - .try_for_each(|c| nb::block!(self.write(*c))) - .map_err(|_| core::fmt::Error) +impl Rx { + /// Reads 9-bit words from the UART/USART + /// + /// If the UART/USART was configured with `WordLength::Bits9`, the returned value will contain + /// 9 received data bits and all other bits set to zero. Otherwise, the returned value will contain + /// 8 received data bits and all other bits set to zero. + pub fn read_u16(&mut self) -> nb::Result { + let usart = unsafe { &*USART::ptr() }; + let sr = usart.sr.read(); + + // Check for any errors + let err = if sr.pe().bit_is_set() { + Some(Error::Parity) + } else if sr.fe().bit_is_set() { + Some(Error::FrameFormat) + } else if sr.ne().bit_is_set() { + Some(Error::Noise) + } else if sr.ore().bit_is_set() { + Some(Error::Overrun) + } else { + None + }; + + if let Some(err) = err { + // Some error occurred. In order to clear that error flag, you have to + // do a read from the sr register followed by a read from the dr register. + let _ = usart.sr.read(); + let _ = usart.dr().read(); + Err(nb::Error::Other(err)) + } else { + // Check if a byte is available + if sr.rxne().bit_is_set() { + // Read the received byte + Ok(usart.dr().read().dr().bits()) + } else { + Err(nb::Error::WouldBlock) + } + } + } + + pub fn read(&mut self) -> nb::Result { + self.read_u16().map(|word16| word16 as u8) + } + + /// Start listening for receive interrupt event + pub fn listen(&mut self) { + unsafe { (*USART::ptr()).cr1.modify(|_, w| w.rxneie().set_bit()) }; } + + /// Stop listening for receive interrupt event + pub fn unlisten(&mut self) { + unsafe { (*USART::ptr()).cr1.modify(|_, w| w.rxneie().clear_bit()) }; + } + + /// Start listening for idle interrupt event + pub fn listen_idle(&mut self) { + unsafe { (*USART::ptr()).cr1.modify(|_, w| w.idleie().set_bit()) }; + } + + /// Stop listening for idle interrupt event + pub fn unlisten_idle(&mut self) { + unsafe { (*USART::ptr()).cr1.modify(|_, w| w.idleie().clear_bit()) }; + } + + /// Returns true if the line idle status is set + pub fn is_idle(&self) -> bool { + unsafe { (*USART::ptr()).sr.read().idle().bit_is_set() } + } + + /// Returns true if the rx register is not empty (and can be read) + pub fn is_rx_not_empty(&self) -> bool { + unsafe { (*USART::ptr()).sr.read().rxne().bit_is_set() } + } + + /// Clear idle line interrupt flag + pub fn clear_idle_interrupt(&self) { + unsafe { + let _ = (*USART::ptr()).sr.read(); + let _ = (*USART::ptr()).dr().read(); + } + } +} + +/// Interrupt event +pub enum Event { + /// New data can be sent + Txe, + /// New data has been received + Rxne, + /// Idle line state detected + Idle, } -/// Ensures that none of the previously written words are still buffered -fn flush(usart: *const SerialRegisterBlock) -> nb::Result<(), Error> { - // NOTE(unsafe) atomic read with no side effects - let sr = unsafe { (*usart).sr.read() }; +impl Serial { + /// Starts listening to the USART by enabling the _Received data + /// ready to be read (RXNE)_ interrupt and _Transmit data + /// register empty (TXE)_ interrupt + pub fn listen(&mut self, event: Event) { + match event { + Event::Rxne => self.rx.listen(), + Event::Txe => self.tx.listen(), + Event::Idle => self.rx.listen_idle(), + } + } + + /// Stops listening to the USART by disabling the _Received data + /// ready to be read (RXNE)_ interrupt and _Transmit data + /// register empty (TXE)_ interrupt + pub fn unlisten(&mut self, event: Event) { + match event { + Event::Rxne => self.rx.unlisten(), + Event::Txe => self.tx.unlisten(), + Event::Idle => self.rx.unlisten_idle(), + } + } + + /// Returns true if the line idle status is set + pub fn is_idle(&self) -> bool { + self.rx.is_idle() + } - if sr.tc().bit_is_set() { - Ok(()) - } else { - Err(nb::Error::WouldBlock) + /// Returns true if the tx register is empty (and can accept data) + pub fn is_tx_empty(&self) -> bool { + self.tx.is_tx_empty() + } + + /// Returns true if the rx register is not empty (and can be read) + pub fn is_rx_not_empty(&self) -> bool { + self.rx.is_rx_not_empty() + } + + /// Clear idle line interrupt flag + pub fn clear_idle_interrupt(&self) { + self.rx.clear_idle_interrupt(); } } -/// Tries to write a byte to the UART -/// Returns `Err(WouldBlock)` if the transmit buffer is full -fn write(usart: *const SerialRegisterBlock, byte: u8) -> nb::Result<(), Error> { - // NOTE(unsafe) atomic read with no side effects - let sr = unsafe { (*usart).sr.read() }; +impl core::fmt::Write for Serial { + fn write_str(&mut self, s: &str) -> core::fmt::Result { + self.tx.write_str(s) + } +} + +pub type Rx1 = Rx; +pub type Tx1 = Tx; +#[cfg(any(feature = "py32f003", feature = "py32f030",))] +pub type Rx2 = Rx; +#[cfg(any(feature = "py32f003", feature = "py32f030",))] +pub type Tx2 = Tx; + +macro_rules! serialdmarx { + ($USARTX:ty: ($dmaX:ty, $dmamux:expr, { + $($rxdma:ident: $ch:literal,)+ + }),) => { + + impl Rx<$USARTX> { + pub fn with_dma( + self, + mut channel: Ch, + ) -> RxDma, Ch> { + unsafe { + // turn on syscfg clock and set mux + pac::SYSCFG::enable(&*pac::RCC::ptr()); + channel.set_map($dmamux); + (*<$USARTX>::ptr()).cr3.modify(|_, w| w.dmar().set_bit()); + } + RxDma { + payload: self, + channel, + } + } + } + + $( + pub type $rxdma = RxDma, Ch<$dmaX, $ch>>; + + impl Receive for $rxdma { + type RxChannel = Ch<$dmaX, $ch>; + type TransmittedWord = u8; + } + + impl TransferPayload for $rxdma { + fn start(&mut self) { + self.channel.start(); + } + fn stop(&mut self) { + self.channel.stop(); + } + } + + impl $rxdma { + pub fn release(mut self) -> (Rx<$USARTX>, Ch<$dmaX, $ch>) { + self.stop(); + unsafe { + (*<$USARTX>::ptr()).cr3.modify(|_, w| w.dmar().clear_bit()); + } + // reset the mux to default + self.channel.set_map(PeriphMap::Adc); + let RxDma { payload, channel } = self; + (payload, channel) + } + } + + impl crate::dma::CircReadDma for $rxdma + where + &'static mut [B; 2]: WriteBuffer, + B: 'static, + { + fn circ_read(mut self, mut buffer: &'static mut [B; 2]) -> CircBuffer { + // NOTE(unsafe) We own the buffer now and we won't call other `&mut` on it + // until the end of the transfer. + let (ptr, len) = unsafe { buffer.write_buffer() }; + self.channel.set_peripheral_address( + unsafe { (*<$USARTX>::ptr()).dr().as_ptr() as u32 }, + false, + ); + self.channel.set_memory_address(ptr as u32, true); + self.channel.set_transfer_length(len); + + atomic::compiler_fence(Ordering::Release); + + self.channel.ch().cr.modify(|_, w| { + w.mem2mem().clear_bit(); + w.pl().medium(); + w.msize().bits8(); + w.psize().bits8(); + w.circ().set_bit(); + w.dir().clear_bit() + }); + + self.start(); + + CircBuffer::new(buffer, self) + } + } + + impl crate::dma::ReadDma for $rxdma + where + B: WriteBuffer, + { + fn read(mut self, mut buffer: B) -> Transfer { + // NOTE(unsafe) We own the buffer now and we won't call other `&mut` on it + // until the end of the transfer. + let (ptr, len) = unsafe { buffer.write_buffer() }; + self.channel.set_peripheral_address( + unsafe { (*<$USARTX>::ptr()).dr().as_ptr() as u32 }, + false, + ); + self.channel.set_memory_address(ptr as u32, true); + self.channel.set_transfer_length(len); + + atomic::compiler_fence(Ordering::Release); + self.channel.ch().cr.modify(|_, w| { + w.mem2mem().clear_bit(); + w.pl().medium(); + w.msize().bits8(); + w.psize().bits8(); + w.circ().clear_bit(); + w.dir().clear_bit() + }); + self.start(); + + Transfer::w(buffer, self) + } + } + + )+ - if sr.txe().bit_is_set() { - // NOTE(unsafe) atomic write to stateless register - unsafe { (*usart).dr8().write(|w| w.dr().bits(byte)) } - Ok(()) - } else { - Err(nb::Error::WouldBlock) } } -/// Tries to read a byte from the UART -fn read(usart: *const SerialRegisterBlock) -> nb::Result { - // NOTE(unsafe) atomic read with no side effects - let sr = unsafe { (*usart).sr.read() }; +#[cfg(any(feature = "py32f003", feature = "py32f030"))] +serialdmarx! { + pac::USART1: (pac::DMA, PeriphMap::Usart1Rx, { + Rx1Dma1: 1, + Rx1Dma2: 2, + Rx1Dma3: 3, + }), +} +#[cfg(any(feature = "py32f003", feature = "py32f030",))] +serialdmarx! { + pac::USART2: (pac::DMA, PeriphMap::Usart2Rx, { + Rx2Dma1: 1, + Rx2Dma2: 2, + Rx2Dma3: 3, + }), +} + +macro_rules! serialdmatx { + ($USARTX:ty: ($dmaX:ty, $dmamux:expr, { + $($txdma:ident: $ch:literal,)+ + }),) => { + + impl Tx<$USARTX> { + pub fn with_dma( + self, + mut channel: Ch, + ) -> TxDma, Ch> { + unsafe { + // turn on syscfg clock and set mux + pac::SYSCFG::enable(&*pac::RCC::ptr()); + channel.set_map($dmamux); + (*<$USARTX>::ptr()).cr3.modify(|_, w| w.dmat().set_bit()); + } + TxDma { + payload: self, + channel, + } + } + } + + $( + pub type $txdma = TxDma, Ch<$dmaX, $ch>>; + + impl Transmit for $txdma { + type TxChannel = Ch<$dmaX, $ch>; + type ReceivedWord = u8; + } + + impl TransferPayload for $txdma { + fn start(&mut self) { + self.channel.start(); + } + fn stop(&mut self) { + self.channel.stop(); + } + } - let dr = unsafe { (*usart).dr8().read() }; + impl $txdma { + pub fn release(mut self) -> (Tx<$USARTX>, Ch<$dmaX, $ch>) { + self.stop(); + unsafe { + (*<$USARTX>::ptr()).cr3.modify(|_, w| w.dmat().clear_bit()); + } + // reset the mux to default + self.channel.set_map(PeriphMap::Adc); + let TxDma { payload, channel } = self; + (payload, channel) + } + } - if sr.pe().bit_is_set() { - Err(nb::Error::Other(Error::Parity)) - } else if sr.fe().bit_is_set() { - Err(nb::Error::Other(Error::Framing)) - } else if sr.ne().bit_is_set() { - Err(nb::Error::Other(Error::Noise)) - } else if sr.ore().bit_is_set() { - Err(nb::Error::Other(Error::Overrun)) - } else if sr.rxne().bit_is_set() { - Ok(dr.dr().bits() as u8) - } else { - Err(nb::Error::WouldBlock) + impl crate::dma::WriteDma for $txdma + where + B: ReadBuffer, + { + fn write(mut self, buffer: B) -> Transfer { + // NOTE(unsafe) We own the buffer now and we won't call other `&mut` on it + // until the end of the transfer. + let (ptr, len) = unsafe { buffer.read_buffer() }; + + self.channel.set_peripheral_address( + unsafe { (*<$USARTX>::ptr()).dr().as_ptr() as u32 }, + false, + ); + + self.channel.set_memory_address(ptr as u32, true); + self.channel.set_transfer_length(len); + + atomic::compiler_fence(Ordering::Release); + + self.channel.ch().cr.modify(|_, w| { + w.mem2mem().clear_bit(); + w.pl().medium(); + w.msize().bits8(); + w.psize().bits8(); + w.circ().clear_bit(); + w.dir().set_bit() + }); + self.start(); + + Transfer::r(buffer, self) + } + } + )+ } } + +#[cfg(any(feature = "py32f003", feature = "py32f030"))] +serialdmatx! { + pac::USART1: (pac::DMA, PeriphMap::Usart1Tx, { + Tx1Dma1: 1, + Tx1Dma2: 2, + Tx1Dma3: 3, + }), +} +#[cfg(any(feature = "py32f003", feature = "py32f030",))] +serialdmatx! { + pac::USART2: (pac::DMA, PeriphMap::Usart2Tx, { + Tx2Dma1: 1, + Tx2Dma2: 2, + Tx2Dma3: 3, + }), +} diff --git a/src/serial/hal_02.rs b/src/serial/hal_02.rs new file mode 100644 index 0000000..e4af8e5 --- /dev/null +++ b/src/serial/hal_02.rs @@ -0,0 +1,132 @@ +use super::*; +use embedded_hal_02::{blocking::serial as blocking, serial}; + +impl serial::Write for Tx { + type Error = Error; + + fn write(&mut self, word: u8) -> nb::Result<(), Self::Error> { + self.write_u8(word) + } + + fn flush(&mut self) -> nb::Result<(), Self::Error> { + self.flush() + } +} + +impl serial::Write for Tx { + type Error = Error; + + fn write(&mut self, word: u16) -> nb::Result<(), Self::Error> { + self.write_u16(word) + } + + fn flush(&mut self) -> nb::Result<(), Self::Error> { + self.flush() + } +} + +impl serial::Read for Rx { + type Error = Error; + + fn read(&mut self) -> nb::Result { + self.read() + } +} + +impl serial::Read for Rx { + type Error = Error; + + fn read(&mut self) -> nb::Result { + self.read_u16() + } +} + +impl serial::Write for Serial { + type Error = Error; + + fn write(&mut self, word: u8) -> nb::Result<(), Self::Error> { + self.tx.write_u8(word) + } + + fn flush(&mut self) -> nb::Result<(), Self::Error> { + self.tx.flush() + } +} + +impl serial::Write for Serial { + type Error = Error; + + fn write(&mut self, word: u16) -> nb::Result<(), Self::Error> { + self.tx.write_u16(word) + } + + fn flush(&mut self) -> nb::Result<(), Self::Error> { + self.tx.flush() + } +} + +impl serial::Read for Serial { + type Error = Error; + + fn read(&mut self) -> nb::Result { + self.rx.read() + } +} + +impl serial::Read for Serial { + type Error = Error; + + fn read(&mut self) -> nb::Result { + self.rx.read_u16() + } +} + +// Blocking + +impl blocking::Write for Tx { + type Error = Error; + + fn bwrite_all(&mut self, buffer: &[u8]) -> Result<(), Self::Error> { + self.bwrite_all_u8(buffer) + } + + fn bflush(&mut self) -> Result<(), Self::Error> { + self.bflush() + } +} + +impl blocking::Write for Tx { + type Error = Error; + + fn bwrite_all(&mut self, buffer: &[u16]) -> Result<(), Self::Error> { + self.bwrite_all_u16(buffer) + } + + fn bflush(&mut self) -> Result<(), Self::Error> { + self.bflush() + } +} + +impl blocking::Write for Serial { + type Error = Error; + + fn bwrite_all(&mut self, buffer: &[u8]) -> Result<(), Self::Error> { + self.tx.bwrite_all_u8(buffer) + } + + fn bflush(&mut self) -> Result<(), Self::Error> { + self.tx.bflush() + } +} + +impl blocking::Write for Serial { + type Error = Error; + + fn bwrite_all(&mut self, buffer: &[u16]) -> Result<(), Self::Error> { + self.tx.bwrite_all_u16(buffer) + } + + fn bflush(&mut self) -> Result<(), Self::Error> { + self.tx.bflush() + } +} diff --git a/src/serial/hal_1.rs b/src/serial/hal_1.rs new file mode 100644 index 0000000..87211d1 --- /dev/null +++ b/src/serial/hal_1.rs @@ -0,0 +1,162 @@ +use super::*; + +mod nb { + use super::{Error, Instance, Rx, Serial, Tx}; + use embedded_hal_nb::serial::ErrorKind; + use embedded_hal_nb::{serial, serial::ErrorType}; + + impl embedded_hal_nb::serial::Error for Error { + fn kind(&self) -> ErrorKind { + match self { + Error::Overrun => ErrorKind::Overrun, + Error::FrameFormat => ErrorKind::FrameFormat, + Error::Parity => ErrorKind::Parity, + Error::Noise => ErrorKind::Noise, + Error::Other => ErrorKind::Other, + } + } + } + + impl ErrorType for Tx { + type Error = Error; + } + + impl ErrorType for Rx { + type Error = Error; + } + + impl ErrorType for Serial { + type Error = Error; + } + + impl serial::Write for Tx { + fn write(&mut self, word: u8) -> nb::Result<(), Self::Error> { + self.write_u8(word)?; + Ok(()) + } + + fn flush(&mut self) -> nb::Result<(), Self::Error> { + self.flush() + } + } + + impl serial::Write for Tx { + fn write(&mut self, word: u16) -> nb::Result<(), Self::Error> { + self.write_u16(word) + } + + fn flush(&mut self) -> nb::Result<(), Self::Error> { + self.flush() + } + } + + impl serial::Read for Rx { + fn read(&mut self) -> nb::Result { + self.read() + } + } + + impl serial::Read for Rx { + fn read(&mut self) -> nb::Result { + self.read_u16() + } + } + + impl serial::Write for Serial { + fn write(&mut self, word: u8) -> nb::Result<(), Self::Error> { + self.tx.write_u8(word).unwrap(); + Ok(()) + } + + fn flush(&mut self) -> nb::Result<(), Self::Error> { + self.tx.flush().unwrap(); + Ok(()) + } + } + + impl serial::Write for Serial { + fn write(&mut self, word: u16) -> nb::Result<(), Self::Error> { + self.tx.write_u16(word).unwrap(); + Ok(()) + } + + fn flush(&mut self) -> nb::Result<(), Self::Error> { + self.tx.flush().unwrap(); + Ok(()) + } + } + + impl serial::Read for Serial { + fn read(&mut self) -> nb::Result { + self.rx.read() + } + } + + impl serial::Read for Serial { + fn read(&mut self) -> nb::Result { + self.rx.read_u16() + } + } +} + +mod io { + use super::super::{Error, Instance, Rx, Serial, Tx}; + use embedded_io::Write; + + impl embedded_io::Error for Error { + // TODO: fix error conversion + fn kind(&self) -> embedded_io::ErrorKind { + embedded_io::ErrorKind::Other + } + } + + impl embedded_io::ErrorType for Serial { + type Error = Error; + } + + impl embedded_io::ErrorType for Tx { + type Error = Error; + } + + impl embedded_io::ErrorType for Rx { + type Error = Error; + } + + impl Write for Tx { + fn write(&mut self, bytes: &[u8]) -> Result { + let mut i = 0; + for byte in bytes.iter() { + match self.write_u8(*byte) { + Ok(_) => { + i += 1; + } + Err(nb::Error::WouldBlock) => { + return Ok(i); + } + Err(nb::Error::Other(e)) => { + return Err(e); + } + } + } + Ok(i) + } + + fn flush(&mut self) -> Result<(), Self::Error> { + self.bflush()?; + Ok(()) + } + } + + impl Write for Serial + where + Tx: Write, + { + fn write(&mut self, bytes: &[u8]) -> Result { + self.tx.write(bytes) + } + + fn flush(&mut self) -> Result<(), Self::Error> { + Write::flush(&mut self.tx) + } + } +} diff --git a/src/spi.rs b/src/spi.rs index 8fbdfd7..779a1c0 100644 --- a/src/spi.rs +++ b/src/spi.rs @@ -14,53 +14,96 @@ //! use crate::hal::pac; //! use crate::hal::prelude::*; //! use crate::hal::spi::{Spi, Mode, Phase, Polarity}; +//! use embedded_hal::spi::SpiBus; //! -//! cortex_m::interrupt::free(|cs| { -//! let mut p = pac::Peripherals::take().unwrap(); -//! let mut rcc = p.RCC.constrain().freeze(&mut p.FLASH); +//! let mut p = pac::Peripherals::take().unwrap(); +//! let mut rcc = p.RCC.constrain().freeze(&mut p.FLASH); //! -//! let gpioa = p.GPIOA.split(&mut rcc); +//! let gpioa = p.GPIOA.split(&mut rcc); //! -//! // Configure pins for SPI -//! let sck = gpioa.pa5.into_alternate_af0(cs); -//! let miso = gpioa.pa6.into_alternate_af0(cs); -//! let mosi = gpioa.pa7.into_alternate_af0(cs); +//! // Configure pins for SPI +//! let sck = gpioa.pa5.into_alternate_af0(); +//! let miso = gpioa.pa6.into_alternate_af0(); +//! let mosi = gpioa.pa7.into_alternate_af0(); //! -//! // Configure SPI with 1MHz rate -//! let mut spi = Spi::spi1(p.SPI1, (sck, miso, mosi), Mode { -//! polarity: Polarity::IdleHigh, -//! phase: Phase::CaptureOnSecondTransition, -//! }, 1.mhz(), &mut rcc); +//! // Configure SPI with 1MHz rate +//! let mut spi = Spi::new(p.SPI1, (Some(sck), Some(miso), Some(mosi)), Mode { +//! polarity: Polarity::IdleHigh, +//! phase: Phase::CaptureOnSecondTransition, +//! }, 1.mhz(), &rcc.clocks); //! -//! let mut data = [0]; -//! loop { -//! spi.transfer(&mut data).unwrap(); -//! } -//! }); +//! let mut data = [0]; +//! let result = [0]; +//! loop { +//! spi.transfer(&mut data, &result).unwrap(); +//! data[0] = result[0]; +//! } //! ``` use core::marker::PhantomData; -use core::ops::Deref; +use core::ops::{Deref, DerefMut}; +use core::ptr; +use core::sync::atomic::{self, Ordering}; -pub use embedded_hal::spi::{ErrorKind, Mode, Phase, Polarity}; +use embedded_dma::{ReadBuffer, WriteBuffer}; -// TODO Put this inside the macro -// Currently that causes a compiler panic -use crate::pac::SPI1; -#[cfg(any(feature = "py32f030",))] -use crate::pac::SPI2; +use crate::pac::{self, RCC}; use crate::gpio::*; -use crate::rcc::{Clocks, Rcc}; +use crate::rcc::{BusClock, Clocks, Enable, Reset}; use crate::time::Hertz; -/// Typestate for 8-bit transfer size -pub struct EightBit; +#[cfg(feature = "with-dma")] +pub mod dma; +mod hal_1; + +/// Clock polarity +#[derive(Clone, Copy, Debug, PartialEq, Eq)] +pub enum Polarity { + /// Clock signal low when idle + IdleLow, + /// Clock signal high when idle + IdleHigh, +} + +/// Clock phase +#[derive(Clone, Copy, Debug, PartialEq, Eq)] +pub enum Phase { + /// Data in "captured" on the first clock transition + CaptureOnFirstTransition, + /// Data in "captured" on the second clock transition + CaptureOnSecondTransition, +} -/// Typestate for 16-bit transfer size -pub struct SixteenBit; +/// SPI mode +#[derive(Clone, Copy, Debug, PartialEq, Eq)] +pub struct Mode { + /// Clock polarity + pub polarity: Polarity, + /// Clock phase + pub phase: Phase, +} + +/// Interrupt event +pub enum Event { + /// New data has been received + Rxne, + /// New data can be sent + Txe, + /// an error condition occurs(Overrun, ModeFault) + Error, +} + +/// The bit format to send the data in +#[derive(Debug, Clone, Copy)] +pub enum SpiBitFormat { + /// Least significant bit first + LsbFirst, + /// Most significant bit first + MsbFirst, +} /// SPI error #[non_exhaustive] @@ -70,27 +113,155 @@ pub enum Error { Overrun, /// Mode fault occurred ModeFault, - /// CRC error - Crc, } -impl ::embedded_hal::spi::Error for Error { - fn kind(&self) -> ErrorKind { - match self { - Error::Overrun => ErrorKind::Overrun, - Error::ModeFault => ErrorKind::ModeFault, - Error::Crc => ErrorKind::Other, - } +pub trait SpiExt: Sized + Instance { + fn spi( + self, + pins: (Option, Option, Option), + mode: Mode, + freq: Hertz, + clocks: &Clocks, + ) -> Spi + where + SCKPIN: SckPin, + MISOPIN: MisoPin, + MOSIPIN: MosiPin; + fn spi_u16( + self, + pins: (Option, Option, Option), + mode: Mode, + freq: Hertz, + clocks: &Clocks, + ) -> Spi + where + SCKPIN: SckPin, + MISOPIN: MisoPin, + MOSIPIN: MosiPin, + { + Self::spi(self, pins, mode, freq, clocks).frame_size_16bit() + } + fn spi_slave( + self, + pins: (Option, Option, Option), + mode: Mode, + ) -> SpiSlave + where + SCKPIN: SckPin, + MISOPIN: MisoPin, + MOSIPIN: MosiPin; + fn spi_slave_u16( + self, + pins: (Option, Option, Option), + mode: Mode, + ) -> SpiSlave + where + SCKPIN: SckPin, + MISOPIN: MisoPin, + MOSIPIN: MosiPin, + { + Self::spi_slave(self, pins, mode).frame_size_16bit() } } -/// SPI abstraction -pub struct Spi { +impl SpiExt for SPI { + fn spi( + self, + pins: (Option, Option, Option), + mode: Mode, + freq: Hertz, + clocks: &Clocks, + ) -> Spi + where + SCKPIN: SckPin, + MISOPIN: MisoPin, + MOSIPIN: MosiPin, + { + Spi::new(self, pins, mode, freq, clocks) + } + fn spi_slave( + self, + pins: (Option, Option, Option), + mode: Mode, + ) -> SpiSlave + where + SCKPIN: SckPin, + MISOPIN: MisoPin, + MOSIPIN: MosiPin, + { + SpiSlave::new(self, pins, mode) + } +} + +pub struct SpiInner { spi: SPI, - pins: (SCKPIN, MISOPIN, MOSIPIN), - _width: PhantomData, + _framesize: PhantomData, +} + +impl SpiInner { + fn new(spi: SPI) -> Self { + Self { + spi, + _framesize: PhantomData, + } + } +} + +/// Spi in Master mode +pub struct Spi { + inner: SpiInner, + #[allow(clippy::type_complexity)] + pins: (Option, Option, Option), +} + +/// Spi in Slave mode +pub struct SpiSlave { + inner: SpiInner, + #[allow(clippy::type_complexity)] + pins: (Option, Option, Option), +} + +impl Deref for Spi { + type Target = SpiInner; + fn deref(&self) -> &Self::Target { + &self.inner + } +} + +impl DerefMut + for Spi +{ + fn deref_mut(&mut self) -> &mut Self::Target { + &mut self.inner + } } +impl Deref + for SpiSlave +{ + type Target = SpiInner; + fn deref(&self) -> &Self::Target { + &self.inner + } +} + +impl DerefMut + for SpiSlave +{ + fn deref_mut(&mut self) -> &mut Self::Target { + &mut self.inner + } +} + +pub trait Instance: + crate::Sealed + Deref + Enable + Reset + BusClock +{ +} + +impl Instance for pac::SPI1 {} +#[cfg(feature = "py32f030")] +impl Instance for pac::SPI2 {} + pub trait SckPin {} pub trait MisoPin {} pub trait MosiPin {} @@ -199,60 +370,41 @@ spi_pins! { } } -macro_rules! spi { - ($($SPI:ident: ($spi:ident, $spiXen:ident, $spiXrst:ident, $apbenr:ident, $apbrstr:ident),)+) => { - $( - impl Spi<$SPI, SCKPIN, MISOPIN, MOSIPIN, EightBit> { - /// Creates a new spi instance - pub fn $spi( - spi: $SPI, - pins: (SCKPIN, MISOPIN, MOSIPIN), - mode: Mode, - speed: F, - rcc: &mut Rcc, - ) -> Self - where - SCKPIN: SckPin<$SPI>, - MISOPIN: MisoPin<$SPI>, - MOSIPIN: MosiPin<$SPI>, - F: Into, - { - /* Enable clock for SPI */ - rcc.regs.$apbenr.modify(|_, w| w.$spiXen().set_bit()); - - /* Reset SPI */ - rcc.regs.$apbrstr.modify(|_, w| w.$spiXrst().set_bit()); - rcc.regs.$apbrstr.modify(|_, w| w.$spiXrst().clear_bit()); - - Spi::<$SPI, SCKPIN, MISOPIN, MOSIPIN, EightBit> { spi, pins, _width: PhantomData }.spi_init(mode, speed, rcc.clocks).into_8bit_width() - } - } - )+ - } -} - -spi! { - SPI1: (spi1, spi1en, spi1rst, apbenr2, apbrstr2), -} -#[cfg(feature = "py32f030")] -spi! { - SPI2: (spi2, spi2en, spi2rst, apbenr1, apbrstr1), -} - -// It's s needed for the impls, but rustc doesn't recognize that -#[allow(dead_code)] -type SpiRegisterBlock = crate::pac::spi1::RegisterBlock; - -impl Spi -where - SPI: Deref, +impl + Spi { - fn spi_init(self, mode: Mode, speed: F, clocks: Clocks) -> Self + /// Creates a new spi instance + pub fn new( + spi: SPI, + pins: (Option, Option, Option), + mode: Mode, + speed: F, + clocks: &Clocks, + ) -> Self where + SCKPIN: SckPin, + MISOPIN: MisoPin, + MOSIPIN: MosiPin, F: Into, { + Self::_new(spi, pins, mode, speed, clocks) + } + + fn _new>( + spi: SPI, + pins: (Option, Option, Option), + mode: Mode, + speed: F, + clocks: &Clocks, + ) -> Self { + /* Enable clock for SPI */ + let rcc = unsafe { &(*RCC::ptr()) }; + SPI::enable(rcc); + /* Reset SPI */ + SPI::reset(rcc); + /* Make sure the SPI unit is disabled so we can configure it */ - self.spi.cr1.modify(|_, w| w.spe().clear_bit()); + spi.cr1.modify(|_, w| w.spe().clear_bit()); let br = match clocks.pclk().0 / speed.into().0 { 0 => unreachable!(), @@ -270,220 +422,306 @@ where // lsbfirst: MSB first // ssm: enable software slave management (NSS pin free for other uses) // ssi: set nss high = master mode - // dff: 8 bit frames // bidimode: 2-line unidirectional // spe: enable the SPI bus - self.spi.cr1.write(|w| { - w.cpha() - .bit(mode.phase == Phase::CaptureOnSecondTransition) - .cpol() - .bit(mode.polarity == Polarity::IdleHigh) - .mstr() - .set_bit() - .br() - .bits(br) - .lsbfirst() - .clear_bit() - .ssm() - .set_bit() - .ssi() - .set_bit() - .rxonly() - .clear_bit() - .bidimode() - .clear_bit() - .spe() - .set_bit() + spi.cr1.write(|w| { + w.cpha().bit(mode.phase == Phase::CaptureOnSecondTransition); + w.cpol().bit(mode.polarity == Polarity::IdleHigh); + w.mstr().set_bit(); + w.br().bits(br); + w.lsbfirst().clear_bit(); + w.ssm().set_bit(); + w.ssi().set_bit(); + w.rxonly().clear_bit(); + w.bidimode().clear_bit(); + w.spe().set_bit() }); + // fifo reception threshold set to 1/4 + #[cfg(not(feature = "py32f002b"))] + spi.cr2.modify(|_, w| w.frxth().quarter()); - self + Spi:: { + inner: SpiInner::new(spi), + pins, + } } - pub fn into_8bit_width(self) -> Spi { - // FRXTH: 8-bit threshold on RX FIFO - // DS: 8-bit data size - // SSOE: cleared to disable SS output - #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] - self.spi - .cr2 - .write(|w| w.frxth().set_bit().ds().eight_bit().ssoe().clear_bit()); - #[cfg(feature = "py32f002b")] - self.spi - .cr2 - .write(|w| w.ds().eight_bit().ssoe().clear_bit()); + pub fn release(self) -> (SPI, (Option, Option, Option)) { + (self.inner.spi, self.pins) + } +} - Spi { - spi: self.spi, - pins: self.pins, - _width: PhantomData, - } +impl + SpiSlave +{ + /// Creates a new spi slave instance + pub fn new( + spi: SPI, + pins: (Option, Option, Option), + mode: Mode, + ) -> Self + where + SCKPIN: SckPin, + MISOPIN: MisoPin, + MOSIPIN: MosiPin, + { + Self::_new(spi, pins, mode) } - pub fn into_16bit_width(self) -> Spi { - // FRXTH: 16-bit threshold on RX FIFO - // DS: 8-bit data size - // SSOE: cleared to disable SS output - #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] - self.spi - .cr2 - .write(|w| w.frxth().set_bit().ds().sixteen_bit().ssoe().clear_bit()); - #[cfg(feature = "py32f002b")] - self.spi - .cr2 - .write(|w| w.ds().sixteen_bit().ssoe().clear_bit()); + fn _new( + spi: SPI, + pins: (Option, Option, Option), + mode: Mode, + ) -> Self { + // enable and reset SPI + let rcc = unsafe { &(*RCC::ptr()) }; + SPI::enable(rcc); + SPI::reset(rcc); + + // disable SS output + spi.cr2.write(|w| w.ssoe().clear_bit()); + + spi.cr1.write(|w| { + // clock phase from config + w.cpha().bit(mode.phase == Phase::CaptureOnSecondTransition); + // clock polarity from config + w.cpol().bit(mode.polarity == Polarity::IdleHigh); + // mstr: slave configuration + w.mstr().clear_bit(); + // lsbfirst: MSB first + w.lsbfirst().clear_bit(); + // ssm: enable software slave management (NSS pin free for other uses) + w.ssm().set_bit(); + // ssi: set nss low = slave mode + w.ssi().clear_bit(); + // bidimode: 2-line unidirectional + w.bidimode().clear_bit(); + // both TX and RX are used + w.rxonly().clear_bit(); + // spe: enable the SPI bus + w.spe().set_bit() + }); - Spi { - spi: self.spi, - pins: self.pins, - _width: PhantomData, + SpiSlave:: { + inner: SpiInner::new(spi), + pins, } } - fn set_send_only(&mut self) { - self.spi - .cr1 - .modify(|_, w| w.bidimode().set_bit().bidioe().set_bit()); + pub fn release(self) -> (SPI, (Option, Option, Option)) { + (self.inner.spi, self.pins) } +} - fn set_bidi(&mut self) { +impl SpiInner { + /// Select which frame format is used for data transfers + pub fn bit_format(&mut self, format: SpiBitFormat) { self.spi .cr1 - .modify(|_, w| w.bidimode().clear_bit().bidioe().clear_bit()); + .modify(|_, w| w.lsbfirst().bit(matches!(format, SpiBitFormat::LsbFirst))); } - fn check_read(&mut self) -> nb::Result<(), Error> { - let sr = self.spi.sr.read(); - - Err(if sr.ovr().bit_is_set() { - nb::Error::Other(Error::Overrun) - } else if sr.modf().bit_is_set() { - nb::Error::Other(Error::ModeFault) - } else if sr.rxne().bit_is_set() { - return Ok(()); - } else { - nb::Error::WouldBlock - }) + /// Starts listening to the SPI by enabling the _Received data + /// ready to be read (RXNE)_ interrupt and _Transmit data + /// register empty (TXE)_ interrupt + pub fn listen(&mut self, event: Event) { + self.spi.cr2.modify(|_, w| match event { + Event::Rxne => w.rxneie().set_bit(), + Event::Txe => w.txeie().set_bit(), + Event::Error => w.errie().set_bit(), + }); } - fn send_buffer_size(&mut self) -> u8 { - match self.spi.sr.read().ftlvl().bits() { - // FIFO empty - 0 => 4, - // FIFO 1/4 full - 1 => 3, - // FIFO 1/2 full - 2 => 2, - // FIFO full - _ => 0, - } + /// Stops listening to the SPI by disabling the _Received data + /// ready to be read (RXNE)_ interrupt and _Transmit data + /// register empty (TXE)_ interrupt + pub fn unlisten(&mut self, event: Event) { + self.spi.cr2.modify(|_, w| match event { + Event::Rxne => w.rxneie().clear_bit(), + Event::Txe => w.txeie().clear_bit(), + Event::Error => w.errie().clear_bit(), + }); } - fn check_send(&mut self) -> nb::Result<(), Error> { - let sr = self.spi.sr.read(); + /// Returns true if the tx register is empty (and can accept data) + #[inline] + pub fn is_tx_empty(&self) -> bool { + self.spi.sr.read().txe().bit_is_set() + } - Err(if sr.ovr().bit_is_set() { - nb::Error::Other(Error::Overrun) - } else if sr.modf().bit_is_set() { - nb::Error::Other(Error::ModeFault) - } else if sr.txe().bit_is_set() && sr.bsy().bit_is_clear() { - return Ok(()); - } else { - nb::Error::WouldBlock - }) + /// Returns true if the rx register is not empty (and can be read) + #[inline] + pub fn is_rx_not_empty(&self) -> bool { + self.spi.sr.read().rxne().bit_is_set() } - fn read_u8(&mut self) -> u8 { - self.spi.dr8().read().bits() as _ + /// Returns true if the transfer is in progress + #[inline] + pub fn is_busy(&self) -> bool { + self.spi.sr.read().bsy().bit_is_set() } - fn send_u8(&mut self, byte: u8) { - self.spi.dr8().write(|w| w.dr().bits(byte as _)); + /// Returns true if data are received and the previous data have not yet been read from SPI_DR. + #[inline] + pub fn is_overrun(&self) -> bool { + self.spi.sr.read().ovr().bit_is_set() } +} - fn read_u16(&mut self) -> u16 { - self.spi.dr().read().bits() as _ +impl Spi { + /// Converts from 8bit dataframe to 16bit. + pub fn frame_size_16bit(self) -> Spi { + self.spi.cr1.modify(|_, w| w.spe().clear_bit()); + self.spi.cr2.modify(|_, w| { + w.ds().set_bit(); + #[cfg(not(feature = "py32f002b"))] + w.frxth().half(); + w + }); + self.spi.cr1.modify(|_, w| w.spe().set_bit()); + Spi { + inner: SpiInner::new(self.inner.spi), + pins: self.pins, + } } +} - fn send_u16(&mut self, byte: u16) { - self.spi.dr().write(|w| w.dr().bits(byte as _)); +impl SpiSlave { + /// Converts from 8bit dataframe to 16bit. + pub fn frame_size_16bit(self) -> SpiSlave { + self.spi.cr1.modify(|_, w| w.spe().clear_bit()); + self.spi.cr2.modify(|_, w| { + w.ds().set_bit(); + #[cfg(not(feature = "py32f002b"))] + w.frxth().half(); + w + }); + self.spi.cr1.modify(|_, w| w.spe().set_bit()); + SpiSlave { + inner: SpiInner::new(self.inner.spi), + pins: self.pins, + } } +} - pub fn release(self) -> (SPI, (SCKPIN, MISOPIN, MOSIPIN)) { - (self.spi, self.pins) +impl Spi { + /// Converts from 16bit dataframe to 8bit. + pub fn frame_size_8bit(self) -> Spi { + self.spi.cr1.modify(|_, w| w.spe().clear_bit()); + self.spi.cr2.modify(|_, w| { + w.ds().clear_bit(); + #[cfg(not(feature = "py32f002b"))] + w.frxth().quarter(); + w + }); + self.spi.cr1.modify(|_, w| w.spe().set_bit()); + Spi { + inner: SpiInner::new(self.inner.spi), + pins: self.pins, + } } +} - pub fn ptr(&self) -> *const SpiRegisterBlock { - self.spi.deref() +impl SpiSlave { + /// Converts from 16bit dataframe to 8bit. + pub fn frame_size_8bit(self) -> SpiSlave { + self.spi.cr1.modify(|_, w| w.spe().clear_bit()); + self.spi.cr2.modify(|_, w| { + w.ds().clear_bit(); + #[cfg(not(feature = "py32f002b"))] + w.frxth().quarter(); + w + }); + self.spi.cr1.modify(|_, w| w.spe().set_bit()); + SpiSlave { + inner: SpiInner::new(self.inner.spi), + pins: self.pins, + } } } -impl ::embedded_hal::spi::ErrorType - for Spi -where - SPI: Deref, -{ - type Error = Error; +pub trait SpiReadWrite { + fn read_data_reg(&mut self) -> T; + fn write_data_reg(&mut self, data: T); + fn spi_write(&mut self, words: &[T]) -> Result<(), Error>; } -impl ::embedded_hal::spi::SpiBus - for Spi -where - SPI: Deref, -{ - fn read(&mut self, words: &mut [u8]) -> Result<(), Self::Error> { - // We want to transfer bidirectionally, make sure we're in the correct mode - self.set_bidi(); - - for word in words.iter_mut() { - nb::block!(self.check_send())?; - self.send_u8(0xFF); - nb::block!(self.check_read())?; - *word = self.read_u8(); - } - Ok(()) +impl SpiReadWrite for SpiInner { + fn read_data_reg(&mut self) -> W { + // NOTE(read_volatile) read only 1 byte (the svd2rust API only allows + // reading a half-word) + unsafe { ptr::read_volatile(self.spi.dr().as_ptr() as *const W) } } - fn write(&mut self, words: &[u8]) -> Result<(), Self::Error> { - self.set_send_only(); - for word in words.iter() { - nb::block!(self.check_send())?; - self.send_u8(*word); - nb::block!(self.check_read())?; - self.read_u8(); - } - Ok(()) + fn write_data_reg(&mut self, data: W) { + // NOTE(write_volatile) see note above + unsafe { ptr::write_volatile(self.spi.dr().as_ptr() as *mut W, data) } } - fn transfer(&mut self, read: &mut [u8], write: &[u8]) -> Result<(), Self::Error> { - // We want to transfer bidirectionally, make sure we're in the correct mode - self.set_bidi(); - - for (rd_word, wr_word) in read.iter_mut().zip(write.iter()) { - nb::block!(self.check_send())?; - self.send_u8(*wr_word); - nb::block!(self.check_read())?; - *rd_word = self.read_u8(); + // Implement write as per the "Transmit only procedure" page 712 + // of RM0008 Rev 20. This is more than twice as fast as the + // default Write<> implementation (which reads and drops each + // received value) + fn spi_write(&mut self, words: &[W]) -> Result<(), Error> { + // Write each word when the tx buffer is empty + for word in words { + loop { + let sr = self.spi.sr.read(); + if sr.txe().bit_is_set() { + self.write_data_reg(*word); + if sr.modf().bit_is_set() { + return Err(Error::ModeFault); + } + break; + } + } } - + // Wait for final TXE + while !self.is_tx_empty() {} + // Wait for final !BSY + while self.is_busy() {} + // Clear OVR set due to dropped received values + let _ = self.read_data_reg(); + let _ = self.spi.sr.read(); Ok(()) } +} - fn transfer_in_place(&mut self, words: &mut [u8]) -> Result<(), Self::Error> { - // We want to transfer bidirectionally, make sure we're in the correct mode - self.set_bidi(); - - for word in words.iter_mut() { - nb::block!(self.check_send())?; - self.send_u8(*word); - nb::block!(self.check_read())?; - *word = self.read_u8(); - } +impl SpiInner +where + SPI: Instance, + W: Copy, +{ + pub fn read_nonblocking(&mut self) -> nb::Result { + let sr = self.spi.sr.read(); - Ok(()) + Err(if sr.ovr().bit_is_set() { + Error::Overrun.into() + } else if sr.modf().bit_is_set() { + Error::ModeFault.into() + } else if sr.rxne().bit_is_set() { + // NOTE(read_volatile) read only 1 byte (the svd2rust API only allows + // reading a half-word) + return Ok(self.read_data_reg()); + } else { + nb::Error::WouldBlock + }) } + pub fn write_nonblocking(&mut self, data: W) -> nb::Result<(), Error> { + let sr = self.spi.sr.read(); - fn flush(&mut self) -> Result<(), Self::Error> { - // no delays required after reads for bus to be idle - Ok(()) + // NOTE: Error::Overrun was deleted in #408. Need check + Err(if sr.modf().bit_is_set() { + Error::ModeFault.into() + } else if sr.txe().bit_is_set() { + // NOTE(write_volatile) see note above + self.write_data_reg(data); + return Ok(()); + } else { + nb::Error::WouldBlock + }) + } + pub fn write(&mut self, words: &[W]) -> Result<(), Error> { + self.spi_write(words) } } diff --git a/src/spi/dma.rs b/src/spi/dma.rs new file mode 100644 index 0000000..58ea977 --- /dev/null +++ b/src/spi/dma.rs @@ -0,0 +1,658 @@ +use super::*; + +// DMA + +use crate::dma::{ + self, dma1, Ch, DmaExt, PeriphMap, ReadDma, ReadWriteDma, Receive, RxDma, RxTxDma, Transfer, + TransferPayload, Transmit, TxDma, WriteDma, +}; + +pub type SpiTxDma = + TxDma, CHANNEL>; +pub type SpiRxDma = + RxDma, CHANNEL>; +pub type SpiRxTxDma = + RxTxDma, RXCHANNEL, TXCHANNEL>; + +pub type SpiSlaveTxDma = + TxDma, CHANNEL>; +pub type SpiSlaveRxDma = + RxDma, CHANNEL>; +pub type SpiSlaveRxTxDma = + RxTxDma, RXCHANNEL, TXCHANNEL>; + +macro_rules! spi_dmarx { + ( + $SPIi:ty: ($dmamux:expr, { + $($rxdma:ident, $slaverxdma:ident: $ch:ty,)+ + }),) => { + + impl Spi<$SPIi, SCKPIN, MISOPIN, MOSIPIN, u8> { + pub fn with_rx_dma(self, mut channel: Ch) -> + SpiRxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, Ch> { + // turn on syscfg clock and set mux + unsafe { pac::SYSCFG::enable(&*pac::RCC::ptr()) }; + channel.set_map($dmamux); + self.spi.cr2.modify(|_, w| w.rxdmaen().set_bit()); + SpiRxDma { + payload: self, + channel, + } + } + } + impl SpiSlave<$SPIi, SCKPIN, MISOPIN, MOSIPIN, u8> { + pub fn with_rx_dma(self, mut channel: Ch) -> + SpiSlaveRxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, Ch> { + // turn on syscfg clock and set mux + unsafe { pac::SYSCFG::enable(&*pac::RCC::ptr()) }; + channel.set_map($dmamux); + self.spi.cr2.modify(|_, w| w.rxdmaen().set_bit()); + SpiSlaveRxDma { + payload: self, + channel, + } + } + } + + $( + pub type $rxdma = SpiRxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch>; + + impl Receive for SpiRxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> { + type RxChannel = $ch; + type TransmittedWord = u8; + } + + impl SpiRxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> { + pub fn release(mut self) -> (Spi<$SPIi, SCKPIN, MISOPIN, MOSIPIN, u8>, $ch) { + self.stop(); + // reset the mux to default + self.channel.set_map(PeriphMap::Adc); + let SpiRxDma { payload, channel } = self; + payload.spi.cr2.modify(|_, w| w.rxdmaen().clear_bit()); + (payload, channel) + } + } + + impl TransferPayload for SpiRxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> { + fn start(&mut self) { + self.channel.start(); + } + fn stop(&mut self) { + self.channel.stop(); + } + } + + impl ReadDma for SpiRxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> + where + B: WriteBuffer, + { + fn read(mut self, mut buffer: B) -> Transfer { + // NOTE(unsafe) We own the buffer now and we won't call other `&mut` on it + // until the end of the transfer. + let (ptr, len) = unsafe { buffer.write_buffer() }; + self.channel.set_peripheral_address( + unsafe { (*<$SPIi>::ptr()).dr().as_ptr() as u32 }, + false, + ); + self.channel.set_memory_address(ptr as u32, true); + self.channel.set_transfer_length(len); + + atomic::compiler_fence(Ordering::Release); + self.channel.ch().cr.modify(|_, w| { + // memory to memory mode disabled + w.mem2mem().clear_bit(); + // medium channel priority level + w.pl().medium(); + // 8-bit memory size + w.msize().bits8(); + // 8-bit peripheral size + w.psize().bits8(); + // circular mode disabled + w.circ().clear_bit(); + // write to memory + w.dir().clear_bit() + }); + self.start(); + + Transfer::w(buffer, self) + } + } + + pub type $slaverxdma = + SpiSlaveRxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch>; + + + impl Receive for SpiSlaveRxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> { + type RxChannel = $ch; + type TransmittedWord = u8; + } + + impl SpiSlaveRxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> { + pub fn release(mut self) -> (SpiSlave<$SPIi, SCKPIN, MISOPIN, MOSIPIN, u8>, $ch) { + self.stop(); + // reset the mux to default + self.channel.set_map(PeriphMap::Adc); + let SpiSlaveRxDma { payload, channel } = self; + payload.spi.cr2.modify(|_, w| w.rxdmaen().clear_bit()); + (payload, channel) + } + } + + impl TransferPayload for SpiSlaveRxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> { + fn start(&mut self) { + self.channel.start(); + } + fn stop(&mut self) { + self.channel.stop(); + } + } + + impl ReadDma for SpiSlaveRxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> + where + B: WriteBuffer, + { + fn read(mut self, mut buffer: B) -> Transfer { + // NOTE(unsafe) We own the buffer now and we won't call other `&mut` on it + // until the end of the transfer. + let (ptr, len) = unsafe { buffer.write_buffer() }; + self.channel.set_peripheral_address( + unsafe { (*<$SPIi>::ptr()).dr().as_ptr() as u32 }, + false, + ); + self.channel.set_memory_address(ptr as u32, true); + self.channel.set_transfer_length(len); + + atomic::compiler_fence(Ordering::Release); + self.channel.ch().cr.modify(|_, w| { + // memory to memory mode disabled + w.mem2mem().clear_bit(); + // medium channel priority level + w.pl().medium(); + // 8-bit memory size + w.msize().bits8(); + // 8-bit peripheral size + w.psize().bits8(); + // circular mode disabled + w.circ().clear_bit(); + // write to memory + w.dir().clear_bit() + }); + self.start(); + + Transfer::w(buffer, self) + } + } + + )+ + + }; +} + +#[cfg(any(feature = "py32f003", feature = "py32f030"))] +spi_dmarx! { + pac::SPI1: (PeriphMap::Spi1Rx, { + Spi1RxDma1, SpiSlave1RxDma1: dma1::C1, + Spi1RxDma2, SpiSlave1RxDma2: dma1::C2, + Spi1RxDma3, SpiSlave1RxDma3: dma1::C3, + }), +} +#[cfg(any(feature = "py32f030"))] +spi_dmarx! { + pac::SPI2: (PeriphMap::Spi2Rx, { + Spi2RxDma1, SpiSlave2RxDma1: dma1::C1, + Spi2RxDma2, SpiSlave2RxDma2: dma1::C2, + Spi2RxDma3, SpiSlave2RxDma3: dma1::C3, + }), +} + +macro_rules! spi_dmatx { + ( + $SPIi:ty: ($dmamux:expr, { + $($txdma:ident, $slavetxdma:ident: $ch:ty,)+ + }),) => { + + impl Spi<$SPIi, SCKPIN, MISOPIN, MOSIPIN, u8> { + pub fn with_tx_dma(self, mut channel: Ch) -> + SpiTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, Ch> { + // turn on syscfg clock and set mux + unsafe { pac::SYSCFG::enable(&*pac::RCC::ptr()) }; + channel.set_map($dmamux); + self.spi.cr2.modify(|_, w| w.txdmaen().set_bit()); + SpiTxDma { + payload: self, + channel, + } + } + } + impl SpiSlave<$SPIi, SCKPIN, MISOPIN, MOSIPIN, u8> { + pub fn with_tx_dma(self, mut channel: Ch) -> + SpiSlaveTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, Ch> { + // turn on syscfg clock and set mux + unsafe { pac::SYSCFG::enable(&*pac::RCC::ptr()) }; + channel.set_map($dmamux); + self.spi.cr2.modify(|_, w| w.txdmaen().set_bit()); + SpiSlaveTxDma { + payload: self, + channel, + } + } + } + + $( + pub type $txdma = SpiTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch>; + + impl Transmit for SpiTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> { + type TxChannel = $ch; + type ReceivedWord = u8; + } + + impl SpiTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> { + pub fn release(mut self) -> (Spi<$SPIi, SCKPIN, MISOPIN, MOSIPIN, u8>, $ch) { + self.stop(); + // reset the mux to default + self.channel.set_map(PeriphMap::Adc); + let SpiTxDma { payload, channel } = self; + payload.spi.cr2.modify(|_, w| w.rxdmaen().clear_bit()); + (payload, channel) + } + } + + impl TransferPayload for SpiTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> { + fn start(&mut self) { + self.channel.start(); + } + fn stop(&mut self) { + self.channel.stop(); + } + } + + impl WriteDma for SpiTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> + where + B: ReadBuffer, + { + fn write(mut self, buffer: B) -> Transfer { + // NOTE(unsafe) We own the buffer now and we won't call other `&mut` on it + // until the end of the transfer. + let (ptr, len) = unsafe { buffer.read_buffer() }; + self.channel.set_peripheral_address( + unsafe { (*<$SPIi>::ptr()).dr().as_ptr() as u32 }, + false, + ); + self.channel.set_memory_address(ptr as u32, true); + self.channel.set_transfer_length(len); + + atomic::compiler_fence(Ordering::Release); + self.channel.ch().cr.modify(|_, w| { + // memory to memory mode disabled + w.mem2mem().clear_bit(); + // medium channel priority level + w.pl().medium(); + // 8-bit memory size + w.msize().bits8(); + // 8-bit peripheral size + w.psize().bits8(); + // circular mode disabled + w.circ().clear_bit(); + // write to memory + w.dir().clear_bit() + }); + self.start(); + + Transfer::r(buffer, self) + } + } + + pub type $slavetxdma = + SpiSlaveTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch>; + + + impl Transmit for SpiSlaveTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> { + type TxChannel = $ch; + type ReceivedWord = u8; + } + + impl SpiSlaveTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> { + pub fn release(mut self) -> (SpiSlave<$SPIi, SCKPIN, MISOPIN, MOSIPIN, u8>, $ch) { + self.stop(); + // reset the mux to default + self.channel.set_map(PeriphMap::Adc); + let SpiSlaveTxDma { payload, channel } = self; + payload.spi.cr2.modify(|_, w| w.txdmaen().clear_bit()); + (payload, channel) + } + } + + impl TransferPayload for SpiSlaveTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> { + fn start(&mut self) { + self.channel.start(); + } + fn stop(&mut self) { + self.channel.stop(); + } + } + + impl WriteDma for SpiSlaveTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $ch> + where + B: ReadBuffer, + { + fn write(mut self, buffer: B) -> Transfer { + // NOTE(unsafe) We own the buffer now and we won't call other `&mut` on it + // until the end of the transfer. + let (ptr, len) = unsafe { buffer.read_buffer() }; + self.channel.set_peripheral_address( + unsafe { (*<$SPIi>::ptr()).dr().as_ptr() as u32 }, + false, + ); + self.channel.set_memory_address(ptr as u32, true); + self.channel.set_transfer_length(len); + + atomic::compiler_fence(Ordering::Release); + self.channel.ch().cr.modify(|_, w| { + // memory to memory mode disabled + w.mem2mem().clear_bit(); + // medium channel priority level + w.pl().medium(); + // 8-bit memory size + w.msize().bits8(); + // 8-bit peripheral size + w.psize().bits8(); + // circular mode disabled + w.circ().clear_bit(); + // read from memory + w.dir().set_bit() + }); + self.start(); + + Transfer::r(buffer, self) + } + } + + )+ + + }; +} + +#[cfg(any(feature = "py32f003", feature = "py32f030"))] +spi_dmatx! { + pac::SPI1: (PeriphMap::Spi1Tx, { + Spi1TxDma1, SpiSlave1TxDma1: dma1::C1, + Spi1TxDma2, SpiSlave1TxDma2: dma1::C2, + Spi1TxDma3, SpiSlave1TxDma3: dma1::C3, + }), +} +#[cfg(any(feature = "py32f030"))] +spi_dmatx! { + pac::SPI2: (PeriphMap::Spi2Tx, { + Spi2TxDma1, SpiSlave2TxDma1: dma1::C1, + Spi2TxDma2, SpiSlave2TxDma2: dma1::C2, + Spi2TxDma3, SpiSlave2TxDma3: dma1::C3, + }), +} + +macro_rules! spi_dmarxtx { + ( + $SPIi:ty: ($dmarxmux:expr, $dmatxmux:expr, { + $($rxtxdma:ident, $slaverxtxdma:ident, ($rxch:ty, $txch:ty),)+ + }),) => { + impl Spi<$SPIi, SCKPIN, MISOPIN, MOSIPIN, u8> { + pub fn with_rx_tx_dma( + self, + mut rxchannel: Ch, + mut txchannel: Ch, + ) -> SpiRxTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, Ch, Ch> { + // turn on syscfg clock and set mux + unsafe { pac::SYSCFG::enable(&*pac::RCC::ptr()) }; + rxchannel.set_map($dmarxmux); + txchannel.set_map($dmatxmux); + self.spi.cr2.modify(|_, w| { + w.rxdmaen().set_bit(); + w.txdmaen().set_bit() + }); + SpiRxTxDma { + payload: self, + rxchannel, + txchannel, + } + } + } + impl SpiSlave<$SPIi, SCKPIN, MISOPIN, MOSIPIN, u8> { + pub fn with_rx_tx_dma( + self, + mut rxchannel: Ch, + mut txchannel: Ch, + ) -> SpiSlaveRxTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, Ch, Ch> { + // turn on syscfg clock and set mux + unsafe { pac::SYSCFG::enable(&*pac::RCC::ptr()) }; + rxchannel.set_map($dmarxmux); + txchannel.set_map($dmatxmux); + self.spi.cr2.modify(|_, w| { + w.rxdmaen().set_bit(); + w.txdmaen().set_bit() + }); + SpiSlaveRxTxDma { + payload: self, + rxchannel, + txchannel, + } + } + } + + $( + pub type $rxtxdma = SpiRxTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $rxch, $txch>; + + impl Transmit for SpiRxTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $rxch, $txch> { + type TxChannel = $txch; + type ReceivedWord = u8; + } + + impl Receive for SpiRxTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $rxch, $txch> { + type RxChannel = $rxch; + type TransmittedWord = u8; + } + + impl SpiRxTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $rxch, $txch> { + pub fn release(mut self) -> (Spi<$SPIi, SCKPIN, MISOPIN, MOSIPIN, u8>, $rxch, $txch) { + self.stop(); + // reset the mux to default + self.rxchannel.set_map(PeriphMap::Adc); + self.txchannel.set_map(PeriphMap::Adc); + let SpiRxTxDma { payload, rxchannel, txchannel } = self; + payload.spi.cr2.modify(|_, w| {w.rxdmaen().clear_bit(); w.txdmaen().clear_bit()}); + (payload, rxchannel, txchannel) + } + } + + impl TransferPayload for SpiRxTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $rxch, $txch> { + fn start(&mut self) { + self.rxchannel.start(); + self.txchannel.start(); + } + fn stop(&mut self) { + self.rxchannel.stop(); + self.txchannel.stop(); + } + } + + impl ReadWriteDma for SpiRxTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $rxch, $txch> + where + RXB: WriteBuffer, + TXB: ReadBuffer, + { + fn read_write(mut self, mut rxbuffer: RXB, txbuffer: TXB) -> Transfer { + // NOTE(unsafe) We own the buffer now and we won't call other `&mut` on it + // until the end of the transfer. + let (rxptr, rxlen) = unsafe { rxbuffer.write_buffer() }; + let (txptr, txlen) = unsafe { txbuffer.read_buffer() }; + + if rxlen != txlen { + panic!("receive and send buffer lengths do not match!"); + } + + self.rxchannel.set_peripheral_address( + unsafe { (*<$SPIi>::ptr()).dr().as_ptr() as u32 }, + false, + ); + self.rxchannel.set_memory_address(rxptr as u32, true); + self.rxchannel.set_transfer_length(rxlen); + + self.txchannel.set_peripheral_address( + unsafe { (*<$SPIi>::ptr()).dr().as_ptr() as u32 }, + false, + ); + self.txchannel.set_memory_address(txptr as u32, true); + self.txchannel.set_transfer_length(txlen); + + atomic::compiler_fence(Ordering::Release); + self.rxchannel.ch().cr.modify(|_, w| { + // memory to memory mode disabled + w.mem2mem().clear_bit(); + // medium channel priority level + w.pl().medium(); + // 8-bit memory size + w.msize().bits8(); + // 8-bit peripheral size + w.psize().bits8(); + // circular mode disabled + w.circ().clear_bit(); + // write to memory + w.dir().clear_bit() + }); + self.txchannel.ch().cr.modify(|_, w| { + // memory to memory mode disabled + w.mem2mem().clear_bit(); + // medium channel priority level + w.pl().medium(); + // 8-bit memory size + w.msize().bits8(); + // 8-bit peripheral size + w.psize().bits8(); + // circular mode disabled + w.circ().clear_bit(); + // read from memory + w.dir().set_bit() + }); + self.start(); + + Transfer::w((rxbuffer, txbuffer), self) + } + } + + pub type $slaverxtxdma = + SpiSlaveRxTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $rxch, $txch>; + + impl Receive for SpiSlaveRxTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $rxch, $txch> { + type RxChannel = $rxch; + type TransmittedWord = u8; + } + + impl Transmit for SpiSlaveRxTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $rxch, $txch> { + type TxChannel = $txch; + type ReceivedWord = u8; + } + + impl SpiSlaveRxTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $rxch, $txch> { + pub fn release(mut self) -> (SpiSlave<$SPIi, SCKPIN, MISOPIN, MOSIPIN, u8>, $rxch, $txch) { + self.stop(); + // reset the mux to default + self.rxchannel.set_map(PeriphMap::Adc); + self.txchannel.set_map(PeriphMap::Adc); + let SpiSlaveRxTxDma { payload, rxchannel, txchannel } = self; + payload.spi.cr2.modify(|_, w| {w.rxdmaen().clear_bit(); w.txdmaen().clear_bit()}); + (payload, rxchannel, txchannel) + } + } + + impl TransferPayload for SpiSlaveRxTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $rxch, $txch> { + fn start(&mut self) { + self.rxchannel.start(); + self.txchannel.start(); + } + fn stop(&mut self) { + self.rxchannel.stop(); + self.txchannel.stop(); + } + } + + impl ReadWriteDma for SpiSlaveRxTxDma<$SPIi, SCKPIN, MISOPIN, MOSIPIN, $rxch, $txch> + where + RXB: WriteBuffer, + TXB: ReadBuffer, + { + fn read_write(mut self, mut rxbuffer: RXB, txbuffer: TXB) -> Transfer { + // NOTE(unsafe) We own the buffer now and we won't call other `&mut` on it + // until the end of the transfer. + let (rxptr, rxlen) = unsafe { rxbuffer.write_buffer() }; + let (txptr, txlen) = unsafe { txbuffer.read_buffer() }; + + if rxlen != txlen { + panic!("receive and send buffer lengths do not match!"); + } + + self.rxchannel.set_peripheral_address( + unsafe { (*<$SPIi>::ptr()).dr().as_ptr() as u32 }, + false, + ); + self.rxchannel.set_memory_address(rxptr as u32, true); + self.rxchannel.set_transfer_length(rxlen); + self.txchannel.set_peripheral_address( + unsafe { (*<$SPIi>::ptr()).dr().as_ptr() as u32 }, + false, + ); + self.txchannel.set_memory_address(txptr as u32, true); + self.txchannel.set_transfer_length(txlen); + + atomic::compiler_fence(Ordering::Release); + self.rxchannel.ch().cr.modify(|_, w| { + // memory to memory mode disabled + w.mem2mem().clear_bit(); + // medium channel priority level + w.pl().medium(); + // 8-bit memory size + w.msize().bits8(); + // 8-bit peripheral size + w.psize().bits8(); + // circular mode disabled + w.circ().clear_bit(); + // write to memory + w.dir().clear_bit() + }); + self.txchannel.ch().cr.modify(|_, w| { + // memory to memory mode disabled + w.mem2mem().clear_bit(); + // medium channel priority level + w.pl().medium(); + // 8-bit memory size + w.msize().bits8(); + // 8-bit peripheral size + w.psize().bits8(); + // circular mode disabled + w.circ().clear_bit(); + // read from memory + w.dir().set_bit() + }); + self.start(); + + Transfer::w((rxbuffer, txbuffer), self) + } + } + + )+ + }; +} + +#[cfg(any(feature = "py32f003", feature = "py32f030"))] +spi_dmarxtx! { + pac::SPI1: (PeriphMap::Spi1Rx, PeriphMap::Spi1Tx, { + Spi1RxTxDma12, SpiSlave1RxTxDma12, (dma1::C1, dma1::C2), + Spi1RxTxDma23, SpiSlave1RxTxDma23, (dma1::C2, dma1::C3), + Spi1RxTxDma13, SpiSlave1RxTxDma13, (dma1::C1, dma1::C3), + }), +} +#[cfg(any(feature = "py32f030"))] +spi_dmarxtx! { + pac::SPI2: (PeriphMap::Spi2Rx, PeriphMap::Spi2Tx, { + Spi2RxTxDma12, SpiSlave2RxTxDma12, (dma1::C1, dma1::C2), + Spi2RxTxDma23, SpiSlave2RxTxDma23, (dma1::C2, dma1::C3), + Spi2RxTxDma13, SpiSlave2RxTxDma13, (dma1::C1, dma1::C3), + }), +} diff --git a/src/spi/hal_02.rs b/src/spi/hal_02.rs new file mode 100644 index 0000000..2e41015 --- /dev/null +++ b/src/spi/hal_02.rs @@ -0,0 +1,70 @@ +use super::*; + +pub use embedded_hal_02::spi::{Mode, Phase, Polarity}; +use embedded_hal_02::{blocking::spi as blocking, spi}; + +impl From for super::Polarity { + fn from(p: Polarity) -> Self { + match p { + Polarity::IdleLow => Self::IdleLow, + Polarity::IdleHigh => Self::IdleHigh, + } + } +} + +impl From for super::Phase { + fn from(p: Phase) -> Self { + match p { + Phase::CaptureOnFirstTransition => Self::CaptureOnFirstTransition, + Phase::CaptureOnSecondTransition => Self::CaptureOnSecondTransition, + } + } +} + +impl From for super::Mode { + fn from(m: Mode) -> Self { + Self { + polarity: m.polarity.into(), + phase: m.phase.into(), + } + } +} + +impl spi::FullDuplex for Spi +where + SPI: Instance, + W: Copy, +{ + type Error = Error; + + fn read(&mut self) -> nb::Result { + self.read_nonblocking() + } + + fn send(&mut self, data: W) -> nb::Result<(), Error> { + self.write_nonblocking(data) + } +} + +impl blocking::transfer::Default for Spi +where + SPI: Instance, + W: Copy, +{ +} + +impl blocking::Write for Spi { + type Error = Error; + + fn write(&mut self, words: &[u8]) -> Result<(), Error> { + self.deref_mut().write(words) + } +} + +impl blocking::Write for Spi { + type Error = Error; + + fn write(&mut self, words: &[u16]) -> Result<(), Error> { + self.deref_mut().write(words) + } +} diff --git a/src/spi/hal_1.rs b/src/spi/hal_1.rs new file mode 100644 index 0000000..b6c095c --- /dev/null +++ b/src/spi/hal_1.rs @@ -0,0 +1,96 @@ +use super::*; +pub use embedded_hal::spi::{ErrorKind, ErrorType, Mode, Phase, Polarity}; + +impl From for super::Polarity { + fn from(p: Polarity) -> Self { + match p { + Polarity::IdleLow => Self::IdleLow, + Polarity::IdleHigh => Self::IdleHigh, + } + } +} + +impl From for super::Phase { + fn from(p: Phase) -> Self { + match p { + Phase::CaptureOnFirstTransition => Self::CaptureOnFirstTransition, + Phase::CaptureOnSecondTransition => Self::CaptureOnSecondTransition, + } + } +} + +impl From for super::Mode { + fn from(m: Mode) -> Self { + Self { + polarity: m.polarity.into(), + phase: m.phase.into(), + } + } +} + +impl embedded_hal::spi::Error for Error { + fn kind(&self) -> ErrorKind { + match self { + Self::Overrun => ErrorKind::Overrun, + Self::ModeFault => ErrorKind::ModeFault, + } + } +} + +impl ErrorType + for Spi +{ + type Error = Error; +} + +mod nb { + use super::{Error, Instance, Spi}; + use embedded_hal_nb::spi::FullDuplex; + + impl FullDuplex + for Spi + where + SPI: Instance, + WIDTH: Copy, + { + fn read(&mut self) -> nb::Result { + self.read_nonblocking() + } + + fn write(&mut self, data: WIDTH) -> nb::Result<(), Error> { + self.write_nonblocking(data) + } + } +} + +mod blocking { + use super::super::{Instance, Spi, SpiReadWrite}; + use embedded_hal::spi::SpiBus; + + impl SpiBus + for Spi + where + SPI: Instance, + WIDTH: Copy + 'static, + { + fn transfer_in_place(&mut self, _words: &mut [WIDTH]) -> Result<(), Self::Error> { + todo!() + } + + fn transfer(&mut self, _buff: &mut [WIDTH], _data: &[WIDTH]) -> Result<(), Self::Error> { + todo!() + } + + fn read(&mut self, _words: &mut [WIDTH]) -> Result<(), Self::Error> { + todo!() + } + + fn write(&mut self, words: &[WIDTH]) -> Result<(), Self::Error> { + self.spi_write(words) + } + + fn flush(&mut self) -> Result<(), Self::Error> { + Ok(()) + } + } +} diff --git a/src/timers.rs b/src/timers.rs index 72402fc..437a788 100644 --- a/src/timers.rs +++ b/src/timers.rs @@ -34,7 +34,7 @@ use cortex_m::peripheral::SYST; use crate::rcc::{Clocks, Rcc}; use crate::time::Hertz; -use embedded_hal::timer::{CountDown, Periodic}; +use embedded_hal_02::timer::{CountDown, Periodic}; use void::Void; /// Hardware timers diff --git a/src/watchdog.rs b/src/watchdog.rs index 2776fa4..b63a245 100644 --- a/src/watchdog.rs +++ b/src/watchdog.rs @@ -41,10 +41,10 @@ //! // Whoops, got stuck, the watchdog issues a reset after 10 ms //! iwdg.feed(); //! ``` -use embedded_hal::watchdog; +use embedded_hal_02::watchdog; -use crate::rcc::Rcc; use crate::pac::IWDG; +use crate::rcc::Rcc; use crate::time::Hertz; /// Watchdog instance From ba844993411401ae9d338e0e4fc18f1da96e5bc9 Mon Sep 17 00:00:00 2001 From: Greg Green Date: Tue, 26 Nov 2024 11:11:26 -0800 Subject: [PATCH 03/11] Updated adc, gpio, i2c, pwm, spi, timers, examples adc mod uses enable and reset added hal_02 module to gpio i2c mod implements Instance trait, uses enable, reset, busclock pwm mod uses enable and reset, bustimerclock added hal_02 module to spi timers mod implements Instance trait, uses enable, reset bustimerclock All examples updated to compile with no warnings --- examples/adc_values.rs | 18 +- examples/blinky.rs | 13 +- examples/blinky_adc.rs | 21 +-- examples/blinky_delay.rs | 9 +- examples/blinky_multiple.rs | 24 ++- examples/blinky_timer.rs | 11 +- examples/blinky_timer_irq.rs | 18 +- examples/flash_systick.rs | 10 +- examples/flash_systick_fancier.rs | 10 +- examples/i2c_find_address.rs | 59 +++--- examples/led_hal_button_irq.rs | 17 +- examples/pwm.rs | 17 +- examples/pwm_complementary.rs | 18 +- examples/serial_echo.rs | 19 +- examples/serial_spi_bridge.rs | 46 ++--- examples/serial_stopwatch.rs | 16 +- examples/spi_hal_apa102c.rs | 24 ++- examples/spi_rc522.rs | 55 +++--- examples/watchdog.rs | 16 +- src/adc.rs | 48 +++-- src/gpio.rs | 41 ++++- src/gpio/hal_02.rs | 291 +++++++++++++----------------- src/gpio/hal_1.rs | 13 +- src/i2c.rs | 46 +++-- src/pwm.rs | 103 ++++------- src/rcc.rs | 1 + src/spi.rs | 1 + src/spi/hal_02.rs | 13 +- src/timers.rs | 58 +++--- 29 files changed, 499 insertions(+), 537 deletions(-) diff --git a/examples/adc_values.rs b/examples/adc_values.rs index b4d4396..dfc1973 100644 --- a/examples/adc_values.rs +++ b/examples/adc_values.rs @@ -8,7 +8,7 @@ use panic_halt as _; use py32f0xx_hal as hal; -use crate::hal::{gpio, pac, prelude::*, rcc::HSIFreq}; +use crate::hal::{gpio, pac, prelude::*}; use cortex_m::{interrupt::Mutex, peripheral::syst::SystClkSource::Core}; use cortex_m_rt::{entry, exception}; @@ -31,9 +31,9 @@ fn main() -> ! { ) { cortex_m::interrupt::free(move |cs| { let mut flash = dp.FLASH; - let mut rcc = dp.RCC.configure().sysclk(24.mhz()).freeze(&mut flash); + let rcc = dp.RCC.configure().sysclk(24.mhz()).freeze(&mut flash); - let gpioa = dp.GPIOA.split(&mut rcc); + let gpioa = dp.GPIOA.split(); let mut syst = cp.SYST; @@ -50,18 +50,18 @@ fn main() -> ! { syst.enable_interrupt(); // USART1 at PA2 (TX) and PA3(RX) - let tx = gpioa.pa2.into_alternate_af1(cs); - let rx = gpioa.pa3.into_alternate_af1(cs); + let tx = gpioa.pa2.into_alternate_af1(); + let rx = gpioa.pa3.into_alternate_af1(); // Initialiase UART let (mut tx, _) = - hal::serial::Serial::usart1(dp.USART1, (tx, rx), 115_200.bps(), &mut rcc).split(); + hal::serial::Serial::new(dp.USART1, (tx, rx), 115_200.bps(), &rcc.clocks).split(); // Initialise ADC - let adc = hal::adc::Adc::new(dp.ADC, &mut rcc, hal::adc::AdcClockMode::default()); + let adc = hal::adc::Adc::new(dp.ADC, hal::adc::AdcClockMode::default()); - let ain0 = gpioa.pa0.into_analog(cs); // ADC_IN0 - let ain1 = gpioa.pa1.into_analog(cs); // ADC_IN1 + let ain0 = gpioa.pa0.into_analog(); // ADC_IN0 + let ain1 = gpioa.pa1.into_analog(); // ADC_IN1 // Output a friendly greeting tx.write_str("\n\rThis ADC example will read various values using the ADC and print them out to the serial terminal\r\n").ok(); diff --git a/examples/blinky.rs b/examples/blinky.rs index d02e09a..9ad9825 100644 --- a/examples/blinky.rs +++ b/examples/blinky.rs @@ -12,25 +12,22 @@ use cortex_m_rt::entry; #[entry] fn main() -> ! { if let Some(mut p) = pac::Peripherals::take() { - let mut rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); + let _rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); - let gpioa = p.GPIOA.split(&mut rcc); + let gpioa = p.GPIOA.split(); // (Re-)configure PA5 as output - let mut led = cortex_m::interrupt::free(|cs| gpioa.pa5.into_push_pull_output(cs)); + let mut led = gpioa.pa5.into_push_pull_output(); - let mut i = 0; loop { // Turn PA5 on a million times in a row for _ in 0..1_000_000 { - led.set_high().ok(); + led.set_high(); } // Then turn PA5 off a million times in a row for _ in 0..1_000_000 { - led.set_low().ok(); + led.set_low(); } - - i += 1; } } diff --git a/examples/blinky_adc.rs b/examples/blinky_adc.rs index f557849..4203107 100644 --- a/examples/blinky_adc.rs +++ b/examples/blinky_adc.rs @@ -9,28 +9,27 @@ use crate::hal::{adc::Adc, delay::Delay, pac, prelude::*}; use cortex_m::peripheral::Peripherals; use cortex_m_rt::entry; +use embedded_hal_02::adc::OneShot; +use embedded_hal_02::blocking::delay::DelayMs; +use embedded_hal_02::digital::v2::ToggleableOutputPin; #[entry] fn main() -> ! { if let (Some(mut p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { - let mut rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); + let rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); - let gpioa = p.GPIOA.split(&mut rcc); + let gpioa = p.GPIOA.split(); - let (mut led, mut an_in) = cortex_m::interrupt::free(move |cs| { - ( - // (Re-)configure PA5 as output - gpioa.pa5.into_push_pull_output(cs), - // (Re-)configure PA0 as analog input - gpioa.pa0.into_analog(cs), - ) - }); + // (Re-)configure PA5 as output + let mut led = gpioa.pa5.into_push_pull_output().downgrade(); + // (Re-)configure PA0 as analog input + let mut an_in = gpioa.pa0.into_analog(); // Get delay provider let mut delay = Delay::new(cp.SYST, &rcc); // Get access to the ADC - let mut adc = Adc::new(p.ADC, &mut rcc, hal::adc::AdcClockMode::Pclk); + let mut adc = Adc::new(p.ADC, hal::adc::AdcClockMode::Pclk); loop { led.toggle().ok(); diff --git a/examples/blinky_delay.rs b/examples/blinky_delay.rs index c64fa07..af64525 100644 --- a/examples/blinky_delay.rs +++ b/examples/blinky_delay.rs @@ -6,19 +6,20 @@ use panic_halt as _; use py32f0xx_hal as hal; use crate::hal::{delay::Delay, pac, prelude::*}; - use cortex_m::peripheral::Peripherals; use cortex_m_rt::entry; +use embedded_hal_02::blocking::delay::DelayMs; +use embedded_hal_02::digital::v2::ToggleableOutputPin; #[entry] fn main() -> ! { if let (Some(mut p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { - let mut rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); + let rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); - let gpioa = p.GPIOA.split(&mut rcc); + let gpioa = p.GPIOA.split(); // (Re-)configure PA5 as output - let mut led = cortex_m::interrupt::free(move |cs| gpioa.pa5.into_push_pull_output(cs)); + let mut led = gpioa.pa5.into_push_pull_output().downgrade(); // Get delay provider let mut delay = Delay::new(cp.SYST, &rcc); diff --git a/examples/blinky_multiple.rs b/examples/blinky_multiple.rs index b19177c..fde11a4 100644 --- a/examples/blinky_multiple.rs +++ b/examples/blinky_multiple.rs @@ -9,23 +9,21 @@ use crate::hal::{delay::Delay, pac, prelude::*}; use cortex_m::peripheral::Peripherals; use cortex_m_rt::entry; +use embedded_hal::digital::OutputPin; +use embedded_hal_02::blocking::delay::DelayMs; #[entry] fn main() -> ! { if let (Some(mut p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { - let mut rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); - - let gpioa = p.GPIOA.split(&mut rcc); - let gpiob = p.GPIOB.split(&mut rcc); - - let (led1, led2) = cortex_m::interrupt::free(move |cs| { - ( - // (Re-)configure PA5 as output - gpioa.pa5.into_push_pull_output(cs), - // (Re-)configure PB1 as output - gpiob.pb1.into_push_pull_output(cs), - ) - }); + let rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); + + let gpioa = p.GPIOA.split(); + let gpiob = p.GPIOB.split(); + + // (Re-)configure PA5 as output + let led1 = gpioa.pa5.into_push_pull_output(); + // (Re-)configure PB1 as output + let led2 = gpiob.pb1.into_push_pull_output(); // Get delay provider let mut delay = Delay::new(cp.SYST, &rcc); diff --git a/examples/blinky_timer.rs b/examples/blinky_timer.rs index 744ff21..ab4fbd8 100644 --- a/examples/blinky_timer.rs +++ b/examples/blinky_timer.rs @@ -9,18 +9,21 @@ use crate::hal::{pac, prelude::*, time::Hertz, timers::*}; use cortex_m_rt::entry; +use embedded_hal_02::digital::v2::ToggleableOutputPin; +use embedded_hal_02::timer::CountDown; + #[entry] fn main() -> ! { if let Some(mut p) = pac::Peripherals::take() { - let mut rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); + let rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); - let gpioa = p.GPIOA.split(&mut rcc); + let gpioa = p.GPIOA.split(); // (Re-)configure PA5 as output - let mut led = cortex_m::interrupt::free(move |cs| gpioa.pa5.into_push_pull_output(cs)); + let mut led = gpioa.pa5.into_push_pull_output().downgrade(); // Set up a timer expiring after 1s - let mut timer = Timer::tim1(p.TIM1, Hertz(5), &mut rcc); + let mut timer = Timer::tim1(p.TIM1, Hertz(5), &rcc.clocks); loop { led.toggle().ok(); diff --git a/examples/blinky_timer_irq.rs b/examples/blinky_timer_irq.rs index b2304db..93cf182 100644 --- a/examples/blinky_timer_irq.rs +++ b/examples/blinky_timer_irq.rs @@ -1,26 +1,26 @@ #![no_main] #![no_std] -use hal::rcc::HSIFreq; use panic_halt as _; use py32f0xx_hal as hal; use crate::hal::{ - gpio::*, + gpio::{Output, Pin, PushPull}, pac::{interrupt, Interrupt, Peripherals, TIM16}, prelude::*, time::Hertz, timers::*, }; -use cortex_m_rt::entry; - use core::cell::RefCell; use cortex_m::{interrupt::Mutex, peripheral::Peripherals as c_m_Peripherals}; +use cortex_m_rt::entry; +use embedded_hal_02::digital::v2::ToggleableOutputPin; +use embedded_hal_02::timer::CountDown; // A type definition for the GPIO pin to be used for our LED -type LEDPIN = gpioa::PA5>; +type LEDPIN = Pin>; // Make LED pin globally available static GLED: Mutex>> = Mutex::new(RefCell::new(None)); @@ -57,23 +57,23 @@ fn TIM16() { fn main() -> ! { if let (Some(mut p), Some(cp)) = (Peripherals::take(), c_m_Peripherals::take()) { cortex_m::interrupt::free(move |cs| { - let mut rcc = p + let rcc = p .RCC .configure() .sysclk(24.mhz()) .pclk(24.mhz()) .freeze(&mut p.FLASH); - let gpioa = p.GPIOA.split(&mut rcc); + let gpioa = p.GPIOA.split(); // (Re-)configure PA5 as output - let led = gpioa.pa5.into_push_pull_output(cs); + let led = gpioa.pa5.into_push_pull_output().downgrade(); // Move the pin into our global storage *GLED.borrow(cs).borrow_mut() = Some(led); // Set up a timer expiring after 1s - let mut timer = Timer::tim16(p.TIM16, Hertz(10), &mut rcc); + let mut timer = Timer::tim16(p.TIM16, Hertz(10), &rcc.clocks); // Generate an interrupt when the timer expires timer.listen(Event::TimeOut); diff --git a/examples/flash_systick.rs b/examples/flash_systick.rs index de5d143..d3c7e5e 100644 --- a/examples/flash_systick.rs +++ b/examples/flash_systick.rs @@ -23,12 +23,12 @@ static GPIO: Mutex>>>> = Mutex::new(R fn main() -> ! { if let (Some(mut p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { cortex_m::interrupt::free(move |cs| { - let mut rcc = p.RCC.configure().sysclk(24.mhz()).freeze(&mut p.FLASH); + let _rcc = p.RCC.configure().sysclk(24.mhz()).freeze(&mut p.FLASH); - let gpioa = p.GPIOA.split(&mut rcc); + let gpioa = p.GPIOA.split(); // (Re-)configure PA5 as output - let led = gpioa.pa5.into_push_pull_output(cs); + let led = gpioa.pa5.into_push_pull_output(); // Transfer GPIO into a shared structure *GPIO.borrow(cs).borrow_mut() = Some(led); @@ -71,13 +71,13 @@ fn SysTick() { // Check state variable, keep LED off most of the time and turn it on every 10th tick if *STATE < 10 { // Turn off the LED - led.set_low().ok(); + led.set_low(); // And now increment state variable *STATE += 1; } else { // Turn on the LED - led.set_high().ok(); + led.set_high(); // And set new state variable back to 0 *STATE = 0; diff --git a/examples/flash_systick_fancier.rs b/examples/flash_systick_fancier.rs index 59bc43a..7174c37 100644 --- a/examples/flash_systick_fancier.rs +++ b/examples/flash_systick_fancier.rs @@ -23,13 +23,13 @@ static GPIO: Mutex>> = Mutex::new(RefCell::new(None)); fn main() -> ! { if let (Some(mut p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { cortex_m::interrupt::free(move |cs| { - let mut rcc = p.RCC.configure().sysclk(24.mhz()).freeze(&mut p.FLASH); + let _rcc = p.RCC.configure().sysclk(24.mhz()).freeze(&mut p.FLASH); // Get access to individual pins in the GPIO port - let gpioa = p.GPIOA.split(&mut rcc); + let gpioa = p.GPIOA.split(); // (Re-)configure the pin connected to our LED as output - let led = gpioa.pa5.into_push_pull_output(cs); + let led = gpioa.pa5.into_push_pull_output(); // Transfer GPIO into a shared structure swap(&mut Some(led), &mut GPIO.borrow(cs).borrow_mut()); @@ -73,13 +73,13 @@ fn SysTick() { // Check state variable, keep LED off most of the time and turn it on every 10th tick if *STATE < 10 { // Turn off the LED - led.set_low().ok(); + led.set_low(); // And now increment state variable *STATE += 1; } else { // Turn on the LED - led.set_high().ok(); + led.set_high(); // And set new state variable back to 0 *STATE = 0; diff --git a/examples/i2c_find_address.rs b/examples/i2c_find_address.rs index 631a797..fafe272 100644 --- a/examples/i2c_find_address.rs +++ b/examples/i2c_find_address.rs @@ -11,44 +11,43 @@ use crate::hal::{i2c::I2c, pac, prelude::*}; use cortex_m_rt::entry; use defmt::info; +use embedded_hal_02::blocking::i2c::Write; /* Example meant for py32f030xc MCUs with i2c devices connected on PB7 and PB8 */ #[entry] fn main() -> ! { if let Some(p) = pac::Peripherals::take() { - cortex_m::interrupt::free(move |cs| { - let mut flash = p.FLASH; - let mut rcc = p - .RCC - .configure() - .sysclk(24.mhz()) - .pclk(24.mhz()) - .freeze(&mut flash); - - let gpioa = p.GPIOA.split(&mut rcc); - - // Configure pins for I2C - let scl = gpioa.pa3.into_alternate_af12(cs); - let sda = gpioa.pa2.into_alternate_af12(cs); - - // Configure I2C with 100kHz rate - let mut i2c = I2c::i2c(p.I2C, (scl, sda), 100.khz(), &mut rcc); - - let mut devices = 0; - // I2C addresses are 7-bit wide, covering the 0-127 range - for add in 0..=127 { - // The write method sends the specified address and checks for acknowledgement; - // if no ack is given by the slave device the result is Err(), otherwise Ok() - // Since we only care for an acknowledgement the data sent can be empty - if i2c.write(add, &[]).is_ok() { - devices += 1; - } + let mut flash = p.FLASH; + let rcc = p + .RCC + .configure() + .sysclk(24.mhz()) + .pclk(24.mhz()) + .freeze(&mut flash); + + let gpioa = p.GPIOA.split(); + + // Configure pins for I2C + let scl = gpioa.pa3.into_alternate_af12(); + let sda = gpioa.pa2.into_alternate_af12(); + + // Configure I2C with 100kHz rate + let mut i2c = I2c::i2c(p.I2C, (scl, sda), 100.khz(), &rcc.clocks); + + let mut devices = 0; + // I2C addresses are 7-bit wide, covering the 0-127 range + for add in 0..=127 { + // The write method sends the specified address and checks for acknowledgement; + // if no ack is given by the slave device the result is Err(), otherwise Ok() + // Since we only care for an acknowledgement the data sent can be empty + if i2c.write(add, &[]).is_ok() { + devices += 1; } + } - // Here the variable "_devices" counts how many i2c addresses were a hit - info!("{} devices find.\r\n", devices); - }); + // Here the variable "_devices" counts how many i2c addresses were a hit + info!("{} devices find.\r\n", devices); } loop { diff --git a/examples/led_hal_button_irq.rs b/examples/led_hal_button_irq.rs index eb512e9..e84fa27 100644 --- a/examples/led_hal_button_irq.rs +++ b/examples/led_hal_button_irq.rs @@ -16,6 +16,7 @@ use cortex_m::{interrupt::Mutex, peripheral::Peripherals as c_m_Peripherals}; use cortex_m_rt::entry; use core::{cell::RefCell, ops::DerefMut}; +use embedded_hal_02::blocking::delay::DelayMs; // Make our LED globally available static LED: Mutex>>>> = Mutex::new(RefCell::new(None)); @@ -35,20 +36,20 @@ fn main() -> ! { rcc.apbenr2.modify(|_, w| w.syscfgen().set_bit()); let mut flash = p.FLASH; - let mut rcc = rcc.configure().sysclk(8.mhz()).freeze(&mut flash); + let rcc = rcc.configure().sysclk(8.mhz()).freeze(&mut flash); - let gpioa = p.GPIOA.split(&mut rcc); - let gpiob = p.GPIOB.split(&mut rcc); + let gpioa = p.GPIOA.split(); + let gpiob = p.GPIOB.split(); let exti = p.EXTI; // Configure PB2 as input (button) - let _ = gpiob.pb2.into_pull_down_input(cs); + let _ = gpiob.pb2.into_pull_down_input(); // Configure PA5 as output (LED) - let mut led = gpioa.pa5.into_push_pull_output(cs); + let mut led = gpioa.pa5.into_push_pull_output(); // Turn off LED - led.set_low().ok(); + led.set_low(); // Initialise delay provider let delay = Delay::new(cp.SYST, &rcc); @@ -95,13 +96,13 @@ fn EXTI2_3() { INT.borrow(cs).borrow_mut().deref_mut(), ) { // Turn on LED - led.set_high().ok(); + led.set_high(); // Wait a second delay.delay_ms(1_000_u16); // Turn off LED - led.set_low().ok(); + led.set_low(); // Clear event triggering the interrupt exti.pr.write(|w| w.pr2().clear()); diff --git a/examples/pwm.rs b/examples/pwm.rs index 45254cf..659783a 100644 --- a/examples/pwm.rs +++ b/examples/pwm.rs @@ -9,23 +9,22 @@ use cortex_m_rt::entry; use py32f0xx_hal as hal; +use embedded_hal_02::PwmPin; use hal::{pac, prelude::*, pwm}; #[entry] fn main() -> ! { if let Some(mut dp) = pac::Peripherals::take() { // Set up the system clock. - let mut rcc = dp.RCC.configure().sysclk(8.mhz()).freeze(&mut dp.FLASH); + let rcc = dp.RCC.configure().sysclk(8.mhz()).freeze(&mut dp.FLASH); - let gpioa = dp.GPIOA.split(&mut rcc); - let channels = cortex_m::interrupt::free(move |cs| { - ( - gpioa.pa8.into_alternate_af2(cs), // on TIM1_CH1 - gpioa.pa9.into_alternate_af2(cs), // on TIM1_CH2 - ) - }); + let gpioa = dp.GPIOA.split(); + let channels = ( + gpioa.pa8.into_alternate_af2(), // on TIM1_CH1 + gpioa.pa9.into_alternate_af2(), // on TIM1_CH2 + ); - let pwm = pwm::tim1(dp.TIM1, channels, &mut rcc, 20u32.khz()); + let pwm = pwm::tim1(dp.TIM1, channels, &rcc.clocks, 20u32.khz()); let (mut ch1, mut ch2) = pwm; let max_duty = ch1.get_max_duty(); ch1.set_duty(max_duty / 2); diff --git a/examples/pwm_complementary.rs b/examples/pwm_complementary.rs index 705cc54..c553625 100644 --- a/examples/pwm_complementary.rs +++ b/examples/pwm_complementary.rs @@ -10,23 +10,23 @@ use cortex_m_rt::entry; use py32f0xx_hal as hal; +use embedded_hal_02::blocking::delay::DelayMs; +use embedded_hal_02::PwmPin; use hal::{delay::Delay, pac, prelude::*, pwm}; #[entry] fn main() -> ! { if let Some(mut dp) = pac::Peripherals::take() { // Set up the system clock. - let mut rcc = dp.RCC.configure().sysclk(8.mhz()).freeze(&mut dp.FLASH); + let rcc = dp.RCC.configure().sysclk(8.mhz()).freeze(&mut dp.FLASH); - let gpioa = dp.GPIOA.split(&mut rcc); - let channels = cortex_m::interrupt::free(move |cs| { - ( - gpioa.pa8.into_alternate_af2(cs), // on TIM1_CH1 - gpioa.pa7.into_alternate_af2(cs), // on TIM1_CH1N - ) - }); + let gpioa = dp.GPIOA.split(); + let channels = ( + gpioa.pa8.into_alternate_af2(), // on TIM1_CH1 + gpioa.pa7.into_alternate_af2(), // on TIM1_CH1N + ); - let pwm = pwm::tim1(dp.TIM1, channels, &mut rcc, 20u32.khz()); + let pwm = pwm::tim1(dp.TIM1, channels, &rcc.clocks, 20u32.khz()); let (mut ch1, mut ch1n) = pwm; let max_duty = ch1.get_max_duty(); ch1.set_duty(max_duty / 2); diff --git a/examples/serial_echo.rs b/examples/serial_echo.rs index d2ea014..7cb2642 100644 --- a/examples/serial_echo.rs +++ b/examples/serial_echo.rs @@ -15,12 +15,13 @@ use crate::hal::{ }; use cortex_m_rt::entry; +use embedded_hal_02::serial::{Read, Write as OtherWrite}; #[entry] fn main() -> ! { if let Some(p) = pac::Peripherals::take() { let mut flash = p.FLASH; - let mut rcc = p + let rcc = p .RCC .configure() .hsi(HSIFreq::Freq24mhz) @@ -29,21 +30,19 @@ fn main() -> ! { rcc.configure_mco(MCOSrc::Sysclk, MCODiv::NotDivided); - let gpioa = p.GPIOA.split(&mut rcc); + let gpioa = p.GPIOA.split(); - let (tx, rx) = cortex_m::interrupt::free(move |cs| { - ( - gpioa.pa2.into_alternate_af1(cs), - gpioa.pa3.into_alternate_af1(cs), - ) - }); + let (tx, rx) = ( + gpioa.pa2.into_alternate_af1(), + gpioa.pa3.into_alternate_af1(), + ); - let mut serial = Serial::usart1(p.USART1, (tx, rx), 115_200.bps(), &mut rcc); + let mut serial = Serial::new(p.USART1, (tx, rx), 115_200.bps(), &rcc.clocks); serial.write_str("Input any key:\n").ok(); loop { // Wait for reception of a single byte - let received = nb::block!(serial.read()).unwrap(); + let received: u8 = nb::block!(serial.read()).unwrap(); // Send back previously received byte and wait for completion nb::block!(serial.write(received)).ok(); diff --git a/examples/serial_spi_bridge.rs b/examples/serial_spi_bridge.rs index b410e57..46d1278 100644 --- a/examples/serial_spi_bridge.rs +++ b/examples/serial_spi_bridge.rs @@ -16,6 +16,7 @@ use crate::hal::{ use nb::block; use cortex_m_rt::entry; +use embedded_hal::spi::SpiBus; /// A basic serial to spi example /// @@ -32,35 +33,38 @@ fn main() -> ! { if let Some(p) = pac::Peripherals::take() { let mut flash = p.FLASH; - let mut rcc = p.RCC.configure().freeze(&mut flash); + let rcc = p.RCC.configure().freeze(&mut flash); - let gpioa = p.GPIOA.split(&mut rcc); + let gpioa = p.GPIOA.split(); - let (sck, miso, mosi, tx, rx) = cortex_m::interrupt::free(move |cs| { - ( - // SPI pins - gpioa.pa5.into_alternate_af0(cs), - gpioa.pa6.into_alternate_af0(cs), - gpioa.pa7.into_alternate_af0(cs), - // USART pins - gpioa.pa2.into_alternate_af1(cs), - gpioa.pa3.into_alternate_af1(cs), - ) - }); + let (sck, miso, mosi, tx, rx) = ( + // SPI pins + gpioa.pa5.into_alternate_af0(), + gpioa.pa6.into_alternate_af0(), + gpioa.pa7.into_alternate_af0(), + // USART pins + gpioa.pa2.into_alternate_af1(), + gpioa.pa3.into_alternate_af1(), + ); // Configure SPI with 1MHz rate - let mut spi = Spi::spi1(p.SPI1, (sck, miso, mosi), MODE, 1.mhz(), &mut rcc); + let mut spi = Spi::new( + p.SPI1, + (Some(sck), Some(miso), Some(mosi)), + MODE, + 1.mhz(), + &rcc.clocks, + ); - let serial = Serial::usart1(p.USART1, (tx, rx), 115_200.bps(), &mut rcc); + let mut serial = Serial::new(p.USART1, (tx, rx), 115_200.bps(), &rcc.clocks); - let (mut tx, mut rx) = serial.split(); - - let mut data = [0]; + let mut datatx = [0]; + let datarx = [0]; loop { - let serial_received = block!(rx.read()).unwrap(); + let serial_received = block!(serial.rx.read()).unwrap(); spi.write(&[serial_received]).ok(); - let spi_received = spi.transfer(&mut data).unwrap(); - block!(tx.write(spi_received[0])).ok(); + spi.transfer(&mut datatx, &datarx).unwrap(); + block!(serial.tx.write_u8(datarx[0])).ok(); } } diff --git a/examples/serial_stopwatch.rs b/examples/serial_stopwatch.rs index 5bf7a92..bb1278a 100644 --- a/examples/serial_stopwatch.rs +++ b/examples/serial_stopwatch.rs @@ -14,9 +14,9 @@ use crate::hal::{ use core::cell::RefCell; use core::fmt::Write as _; use core::ops::DerefMut; - use cortex_m::{interrupt::Mutex, peripheral::Peripherals as c_m_Peripherals}; use cortex_m_rt::entry; +use embedded_hal_02::timer::CountDown; // Make timer interrupt registers globally available static GINT: Mutex>>> = Mutex::new(RefCell::new(None)); @@ -59,15 +59,15 @@ fn main() -> ! { if let (Some(p), Some(cp)) = (Peripherals::take(), c_m_Peripherals::take()) { let mut serial = cortex_m::interrupt::free(move |cs| { let mut flash = p.FLASH; - let mut rcc = p.RCC.configure().sysclk(24.mhz()).freeze(&mut flash); + let rcc = p.RCC.configure().sysclk(24.mhz()).freeze(&mut flash); // Use USART1 with PA2 and PA3 as serial port - let gpioa = p.GPIOA.split(&mut rcc); - let tx = gpioa.pa2.into_alternate_af1(cs); - let rx = gpioa.pa3.into_alternate_af1(cs); + let gpioa = p.GPIOA.split(); + let tx = gpioa.pa2.into_alternate_af1(); + let rx = gpioa.pa3.into_alternate_af1(); // Set up a timer expiring every millisecond - let mut timer = Timer::tim16(p.TIM16, 1000.hz(), &mut rcc); + let mut timer = Timer::tim16(p.TIM16, 1000.hz(), &rcc.clocks); // Generate an interrupt when the timer expires timer.listen(Event::TimeOut); @@ -84,7 +84,7 @@ fn main() -> ! { cortex_m::peripheral::NVIC::unpend(Interrupt::TIM16); // Set up our serial port - Serial::usart1(p.USART1, (tx, rx), 115_200.bps(), &mut rcc) + Serial::new(p.USART1, (tx, rx), 115_200.bps(), &rcc.clocks) }); // Print a welcome message @@ -96,7 +96,7 @@ fn main() -> ! { loop { // Wait for reception of a single byte - let received = nb::block!(serial.read()).unwrap(); + let received = nb::block!(serial.rx.read()).unwrap(); let time = cortex_m::interrupt::free(|cs| { let mut time = TIME.borrow(cs).borrow_mut(); diff --git a/examples/spi_hal_apa102c.rs b/examples/spi_hal_apa102c.rs index 80da28c..6725a16 100644 --- a/examples/spi_hal_apa102c.rs +++ b/examples/spi_hal_apa102c.rs @@ -23,21 +23,25 @@ fn main() -> ! { if let Some(p) = pac::Peripherals::take() { let mut flash = p.FLASH; - let mut rcc = p.RCC.configure().freeze(&mut flash); + let rcc = p.RCC.configure().freeze(&mut flash); - let gpioa = p.GPIOA.split(&mut rcc); + let gpioa = p.GPIOA.split(); // Configure pins for SPI - let (sck, miso, mosi) = cortex_m::interrupt::free(move |cs| { - ( - gpioa.pa5.into_alternate_af0(cs), - gpioa.pa6.into_alternate_af0(cs), - gpioa.pa7.into_alternate_af0(cs), - ) - }); + let (sck, miso, mosi) = ( + gpioa.pa5.into_alternate_af0(), + gpioa.pa6.into_alternate_af0(), + gpioa.pa7.into_alternate_af0(), + ); // Configure SPI with 100kHz rate - let mut spi = Spi::spi1(p.SPI1, (sck, miso, mosi), MODE, 100_000.hz(), &mut rcc); + let mut spi = Spi::new( + p.SPI1, + (Some(sck), Some(miso), Some(mosi)), + MODE, + 100_000.hz(), + &rcc.clocks, + ); // Cycle through colors on 16 chained APA102C LEDs loop { diff --git a/examples/spi_rc522.rs b/examples/spi_rc522.rs index 05a5457..d8d910c 100644 --- a/examples/spi_rc522.rs +++ b/examples/spi_rc522.rs @@ -10,22 +10,19 @@ use crate::hal::{ delay::Delay, pac, prelude::*, - serial::Serial, spi::Spi, spi::{Mode, Phase, Polarity}, time::Hertz, timers::Timer, }; - -use nb::block; - use cortex_m_rt::entry; - use defmt::{error, info}; +use embedded_hal_02::blocking::delay::DelayMs; +use embedded_hal_02::digital::v2::OutputPin; +use embedded_hal_02::timer::CountDown; -use mfrc522::comm::{eh02::spi::SpiInterface, Interface}; -use mfrc522::error::Error; -use mfrc522::{Initialized, Mfrc522, Uid}; +use mfrc522::comm::eh02::spi::SpiInterface; +use mfrc522::Mfrc522; /// A basic serial to spi example /// @@ -45,31 +42,35 @@ fn main() -> ! { cortex_m::peripheral::Peripherals::take(), ) { let mut flash = p.FLASH; - let mut rcc = p.RCC.configure().freeze(&mut flash); + let rcc = p.RCC.configure().freeze(&mut flash); let mut delay = Delay::new(cp.SYST, &rcc); - let gpioa = p.GPIOA.split(&mut rcc); - - let (sck, miso, mosi, mut nss, mut rst) = cortex_m::interrupt::free(move |cs| { - ( - // SPI pins - gpioa.pa5.into_alternate_af0(cs), - gpioa.pa6.into_alternate_af0(cs), - gpioa.pa7.into_alternate_af0(cs), - // Aux pins - gpioa.pa4.into_push_pull_output(cs), - gpioa.pa1.into_push_pull_output(cs), - ) - }); - rst.set_low(); + let gpioa = p.GPIOA.split(); + + let (sck, miso, mosi, nss, mut rst) = ( + // SPI pins + gpioa.pa5.into_alternate_af0(), + gpioa.pa6.into_alternate_af0(), + gpioa.pa7.into_alternate_af0(), + // Aux pins + gpioa.pa4.into_push_pull_output().downgrade(), + gpioa.pa1.into_push_pull_output().downgrade(), + ); + rst.set_low().ok(); // Configure SPI with 1MHz rate - let mut spi = Spi::spi1(p.SPI1, (sck, miso, mosi), MODE, 1.mhz(), &mut rcc); + let spi = Spi::new( + p.SPI1, + (Some(sck), Some(miso), Some(mosi)), + MODE, + 1.mhz(), + &rcc.clocks, + ); let itf = SpiInterface::new(spi).with_nss(nss).with_delay(|| { delay.delay_ms(1_u16); }); - rst.set_high(); + rst.set_high().ok(); let mut mfrc522 = Mfrc522::new(itf).init().unwrap(); @@ -77,7 +78,7 @@ fn main() -> ! { info!("MFRC522 version: 0x{:02x}", ver); assert!(ver == 0x91 || ver == 0x92); - let mut timer = Timer::tim1(p.TIM1, Hertz(1), &mut rcc); + let mut timer = Timer::tim1(p.TIM1, Hertz(1), &rcc.clocks); loop { info!("Waiting for card..."); @@ -89,7 +90,7 @@ fn main() -> ! { error!("Failed to select card"); } } - Err(e) => error!("Error when requesting ATQA!"), + Err(_e) => error!("Error when requesting ATQA!"), } nb::block!(timer.wait()).unwrap(); diff --git a/examples/watchdog.rs b/examples/watchdog.rs index 1f29bf7..df9dca8 100644 --- a/examples/watchdog.rs +++ b/examples/watchdog.rs @@ -5,12 +5,12 @@ use panic_halt as _; use py32f0xx_hal as hal; -use crate::hal::{delay::Delay, pac, prelude::*, serial::Serial, time::Hertz, watchdog::Watchdog}; - +use crate::hal::{delay::Delay, pac, prelude::*, serial::Serial, time::Hertz, watchdog}; +use core::fmt::Write; use cortex_m::peripheral::Peripherals; use cortex_m_rt::entry; - -use core::fmt::Write; +use embedded_hal_02::blocking::delay::DelayMs; +use embedded_hal_02::watchdog::{Watchdog, WatchdogEnable}; #[entry] fn main() -> ! { @@ -18,22 +18,22 @@ fn main() -> ! { let mut flash = p.FLASH; let mut rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut flash); - let gpioa = p.GPIOA.split(&mut rcc); + let gpioa = p.GPIOA.split(); let dbg = p.DBG; // Disable the watchdog when the cpu is stopped under debug dbg.apb_fz1.modify(|_, w| w.dbg_iwdg_stop().set_bit()); - let mut watchdog = Watchdog::new(&mut rcc, p.IWDG); + let mut watchdog = watchdog::Watchdog::new(&mut rcc, p.IWDG); // Get delay provider let mut delay = Delay::new(cp.SYST, &rcc); // Configure serial TX pin - let tx = cortex_m::interrupt::free(move |cs| gpioa.pa2.into_alternate_af1(cs)); + let tx = gpioa.pa2.into_alternate_af1(); // Obtain a serial peripheral with for unidirectional communication - let mut serial = Serial::usart1tx(p.USART1, tx, 115_200.bps(), &mut rcc); + let mut serial = Serial::new(p.USART1, (tx, ()), 115_200.bps(), &rcc.clocks); serial.write_str("RESET \r\n").ok(); diff --git a/src/adc.rs b/src/adc.rs index 78674f9..5ccb4ce 100644 --- a/src/adc.rs +++ b/src/adc.rs @@ -12,29 +12,27 @@ //! use crate::hal::prelude::*; //! use crate::hal::adc::Adc; //! -//! cortex_m::interrupt::free(|cs| { -//! let mut p = pac::Peripherals::take().unwrap(); -//! let mut rcc = p.RCC.configure().freeze(&mut p.FLASH); +//! let mut p = pac::Peripherals::take().unwrap(); +//! let rcc = p.RCC.configure().freeze(&mut p.FLASH); //! -//! let gpioa = p.GPIOA.split(&mut rcc); +//! let gpioa = p.GPIOA.split(); //! -//! let mut led = gpioa.pa1.into_push_pull_pull_output(cs); -//! let mut an_in = gpioa.pa0.into_analog(cs); +//! let mut led = gpioa.pa1.into_push_pull_pull_output(); +//! let mut an_in = gpioa.pa0.into_analog(); //! -//! let mut delay = Delay::new(cp.SYST, &rcc); +//! let mut delay = Delay::new(cp.SYST, &rcc); //! -//! let mut adc = Adc::new(p.ADC, &mut rcc); +//! let mut adc = Adc::new(p.ADC); //! -//! loop { -//! let val: u16 = adc.read(&mut an_in).unwrap(); -//! if val < ((1 << 8) - 1) { -//! led.set_low(); -//! } else { -//! led.set_high(); -//! } -//! delay.delay_ms(50_u16); +//! loop { +//! let val: u16 = adc.read(&mut an_in).unwrap(); +//! if val < ((1 << 8) - 1) { +//! led.set_low(); +//! } else { +//! led.set_high(); //! } -//! }); +//! delay.delay_ms(50_u16); +//! } //! ``` // const VREFCAL: *const u16 = 0x1FFF_0F1A as *const u16; @@ -61,9 +59,9 @@ use crate::{ cfgr2::CKMODE_A, smpr::SMP_A, }, - ADC, + ADC, RCC, }, - rcc::Rcc, + rcc::{Enable, Reset}, }; /// Analog to Digital converter interface @@ -413,14 +411,14 @@ impl Adc { /// Sets all configurable parameters to defaults, enables the HSI14 clock /// for the ADC if it is not already enabled and performs a boot time /// calibration. As such this method may take an appreciable time to run. - pub fn new(adc: ADC, rcc: &mut Rcc, ckmode: AdcClockMode) -> Self { + pub fn new(adc: ADC, ckmode: AdcClockMode) -> Self { let mut s = Self { rb: adc, sample_time: AdcSampleTime::default(), align: AdcAlign::default(), precision: AdcPrecision::default(), }; - s.select_clock(rcc, ckmode); + s.select_clock(ckmode); s.calibrate(); s } @@ -526,10 +524,10 @@ impl Adc { .modify(|_, w| w.dmacfg().bit(dmacfg).dmaen().bit(dmaen)); } - fn select_clock(&mut self, rcc: &mut Rcc, ckmode: AdcClockMode) { - rcc.regs.apbrstr2.modify(|_, w| w.adcrst().reset()); - rcc.regs.apbrstr2.modify(|_, w| w.adcrst().clear_bit()); - rcc.regs.apbenr2.modify(|_, w| w.adcen().enabled()); + fn select_clock(&mut self, ckmode: AdcClockMode) { + let rcc = unsafe { &(*RCC::ptr()) }; + ADC::reset(rcc); + ADC::enable(rcc); self.rb .cfgr2 .modify(|_, w| w.ckmode().variant(ckmode.into())); diff --git a/src/gpio.rs b/src/gpio.rs index 5537c78..dbcb849 100644 --- a/src/gpio.rs +++ b/src/gpio.rs @@ -4,6 +4,7 @@ use core::marker::PhantomData; use crate::pac; +mod hal_02; mod hal_1; pub trait PinExt { @@ -198,36 +199,49 @@ pub struct AF14; pub struct AF15; /// Alternate function mode (type state) +#[derive(Default)] pub struct Alternate { _mode: PhantomData, } /// Input mode (type state) +#[derive(Default)] pub struct Input { _mode: PhantomData, } /// Floating input (type state) +#[derive(Default)] pub struct Floating; /// Pulled down input (type state) +#[derive(Default)] pub struct PullDown; /// Pulled up input (type state) +#[derive(Default)] pub struct PullUp; /// Open drain input or output (type state) +#[derive(Default)] pub struct OpenDrain; /// Analog mode (type state) +#[derive(Default)] pub struct Analog; /// Output mode (type state) +#[derive(Default)] pub struct Output { _mode: PhantomData, } +/// Used by the debugger (type state) +#[derive(Default)] +pub struct Debugger; + /// Push pull output (type state) +#[derive(Default)] pub struct PushPull; /// Fully erased pin @@ -290,7 +304,7 @@ gpio_trait!(gpiof); gpio_trait!(gpioc); macro_rules! gpio { - ([$($GPIOX:ident, $gpiox:ident, $gpioxenr:ident, $PXx:ident, $PCH:literal, $gate:meta => [ + ([$($GPIOX:ident, $gpiox:ident, $PXx:ident, $PCH:literal, $gate:meta => [ $($PXi:ident: ($pxi:ident, $i:expr, $MODE:ty),)+ ]),+]) => { $( @@ -699,18 +713,29 @@ macro_rules! gpio { unsafe { (*$GPIOX::ptr()).set_high($i) }; } - fn set_low(&mut self) { + #[allow(dead_code)] + pub fn set_low(&mut self) { unsafe { (*$GPIOX::ptr()).set_low($i) }; } - fn is_high(&mut self) -> bool { + #[allow(dead_code)] + pub fn is_high(&mut self) -> bool { !self.is_low() } - fn is_low(&mut self) -> bool { + #[allow(dead_code)] + pub fn is_low(&mut self) -> bool { unsafe { (*$GPIOX::ptr()).is_low($i) } } + pub fn toggle(&mut self) { + if self.is_low() { + self.set_high(); + } else { + self.set_low(); + } + } + /// Erases the pin number from the type /// /// This is useful when you want to collect the pins into an array where you @@ -756,7 +781,7 @@ macro_rules! gpio { gpio!([ // BUGBUG: py32f002b only has 8 pins? - GPIOA, gpioa, gpioaen, PA, b'A', any( + GPIOA, gpioa, PA, b'A', any( feature = "device-selected" ) => [ PA0: (pa0, 0, Input), @@ -776,7 +801,7 @@ gpio!([ PA14: (pa14, 14, Input), PA15: (pa15, 15, Input), ], - GPIOB, gpiob, gpioben, PB, b'B', any( + GPIOB, gpiob, PB, b'B', any( feature = "device-selected" ) => [ PB0: (pb0, 0, Input), @@ -789,13 +814,13 @@ gpio!([ PB7: (pb7, 7, Input), PB8: (pb8, 8, Input), ], - GPIOC, gpioc, gpiocen, PC, b'C', any( + GPIOC, gpioc, PC, b'C', any( feature = "py32f002b" ) => [ PC0: (pf0, 0, Input), PC1: (pf1, 1, Input), ], - GPIOF, gpiof, gpiofen, PF, b'F', any( + GPIOF, gpiof, PF, b'F', any( feature = "py32f030", feature = "py32f003", feature = "py32f002a" diff --git a/src/gpio/hal_02.rs b/src/gpio/hal_02.rs index 54baa8a..b25ae16 100644 --- a/src/gpio/hal_02.rs +++ b/src/gpio/hal_02.rs @@ -1,214 +1,173 @@ use super::*; -use embedded_hal_02::digital::v2::{InputPin, OutputPin, StatefulOutputPin, ToggleableOutputPin}; +use core::convert::Infallible; +use embedded_hal_02::digital::v2::{toggleable, InputPin, OutputPin, StatefulOutputPin}; // Pin -impl OutputPin for Pin { - type Error = PinModeError; - fn set_high(&mut self) -> Result<(), Self::Error> { - if self.mode.is_output() { - self._set_state(PinState::High); - Ok(()) - } else { - Err(PinModeError::IncorrectMode) - } - } - fn set_low(&mut self) -> Result<(), Self::Error> { - if self.mode.is_output() { - self._set_state(PinState::Low); - Ok(()) - } else { - Err(PinModeError::IncorrectMode) - } - } -} - -impl InputPin for Pin { - type Error = PinModeError; - fn is_high(&self) -> Result { - self.is_low().map(|b| !b) - } - fn is_low(&self) -> Result { - if self.mode.is_input() { - Ok(self._is_low()) - } else { - Err(PinModeError::IncorrectMode) - } - } -} - -impl OutputPin for Pin> { +impl OutputPin for Pin> { type Error = Infallible; #[inline] fn set_high(&mut self) -> Result<(), Self::Error> { - self.set_high(); + unsafe { (*self.port).set_high(self.i) }; Ok(()) } #[inline] fn set_low(&mut self) -> Result<(), Self::Error> { - self.set_low(); + unsafe { (*self.port).set_low(self.i) }; Ok(()) } } -impl StatefulOutputPin for Pin> { +impl StatefulOutputPin for Pin> { #[inline] fn is_set_high(&self) -> Result { - Ok(self.is_set_high()) + self.is_set_low().map(|v| !v) } #[inline] fn is_set_low(&self) -> Result { - Ok(self.is_set_low()) + Ok(unsafe { (*self.port).is_set_low(self.i) }) } } -impl ToggleableOutputPin for Pin> { - type Error = Infallible; - - #[inline(always)] - fn toggle(&mut self) -> Result<(), Self::Error> { - self.toggle(); - Ok(()) - } -} - -impl InputPin for Pin> { +impl InputPin for Pin> { type Error = Infallible; #[inline] fn is_high(&self) -> Result { - Ok(self.is_high()) + self.is_low().map(|v| !v) } #[inline] fn is_low(&self) -> Result { - Ok(self.is_low()) + Ok(unsafe { (*self.port).is_low(self.i) }) } } -impl InputPin for Pin> { +impl InputPin for Pin> { type Error = Infallible; #[inline] fn is_high(&self) -> Result { - Ok(self.is_high()) + self.is_low().map(|v| !v) } #[inline] fn is_low(&self) -> Result { - Ok(self.is_low()) - } -} - -// PartiallyErasedPin - -impl OutputPin for PartiallyErasedPin> { - type Error = Infallible; - - #[inline(always)] - fn set_high(&mut self) -> Result<(), Self::Error> { - self.set_high(); - Ok(()) - } - - #[inline(always)] - fn set_low(&mut self) -> Result<(), Self::Error> { - self.set_low(); - Ok(()) - } -} - -impl StatefulOutputPin for PartiallyErasedPin> { - #[inline(always)] - fn is_set_high(&self) -> Result { - Ok(self.is_set_high()) - } - - #[inline(always)] - fn is_set_low(&self) -> Result { - Ok(self.is_set_low()) - } -} - -impl ToggleableOutputPin for PartiallyErasedPin> { - type Error = Infallible; - - #[inline(always)] - fn toggle(&mut self) -> Result<(), Self::Error> { - self.toggle(); - Ok(()) - } -} - -impl InputPin for PartiallyErasedPin> { - type Error = Infallible; - - #[inline(always)] - fn is_high(&self) -> Result { - Ok(self.is_high()) - } - - #[inline(always)] - fn is_low(&self) -> Result { - Ok(self.is_low()) + Ok(unsafe { (*self.port).is_low(self.i) }) } } -impl InputPin for PartiallyErasedPin> { - type Error = Infallible; +impl toggleable::Default for Pin> {} - #[inline(always)] - fn is_high(&self) -> Result { - Ok(self.is_high()) - } +// PartiallyErasedPin - #[inline(always)] - fn is_low(&self) -> Result { - Ok(self.is_low()) - } -} +// impl OutputPin for PartiallyErasedPin> { +// type Error = Infallible; + +// #[inline(always)] +// fn set_high(&mut self) -> Result<(), Self::Error> { +// self.set_high(); +// Ok(()) +// } + +// #[inline(always)] +// fn set_low(&mut self) -> Result<(), Self::Error> { +// self.set_low(); +// Ok(()) +// } +// } + +// impl StatefulOutputPin for PartiallyErasedPin> { +// #[inline(always)] +// fn is_set_high(&self) -> Result { +// Ok(self.is_set_high()) +// } + +// #[inline(always)] +// fn is_set_low(&self) -> Result { +// Ok(self.is_set_low()) +// } +// } + +// impl ToggleableOutputPin for PartiallyErasedPin> { +// type Error = Infallible; + +// #[inline(always)] +// fn toggle(&mut self) -> Result<(), Self::Error> { +// self.toggle(); +// Ok(()) +// } +// } + +// impl InputPin for PartiallyErasedPin> { +// type Error = Infallible; + +// #[inline(always)] +// fn is_high(&self) -> Result { +// Ok(self.is_high()) +// } + +// #[inline(always)] +// fn is_low(&self) -> Result { +// Ok(self.is_low()) +// } +// } + +// impl InputPin for PartiallyErasedPin> { +// type Error = Infallible; + +// #[inline(always)] +// fn is_high(&self) -> Result { +// Ok(self.is_high()) +// } + +// #[inline(always)] +// fn is_low(&self) -> Result { +// Ok(self.is_low()) +// } +// } // ErasedPin -impl OutputPin for ErasedPin> { - type Error = Infallible; - fn set_high(&mut self) -> Result<(), Infallible> { - self.set_high(); - Ok(()) - } - - fn set_low(&mut self) -> Result<(), Infallible> { - self.set_low(); - Ok(()) - } -} - -impl StatefulOutputPin for ErasedPin> { - fn is_set_high(&self) -> Result { - Ok(self.is_set_high()) - } - - fn is_set_low(&self) -> Result { - Ok(self.is_set_low()) - } -} - -impl InputPin for ErasedPin> { - type Error = Infallible; - fn is_high(&self) -> Result { - Ok(self.is_high()) - } - - fn is_low(&self) -> Result { - Ok(self.is_low()) - } -} - -impl InputPin for ErasedPin> { - type Error = Infallible; - fn is_high(&self) -> Result { - Ok(self.is_high()) - } - - fn is_low(&self) -> Result { - Ok(self.is_low()) - } -} +// impl OutputPin for ErasedPin> { +// type Error = Infallible; +// fn set_high(&mut self) -> Result<(), Infallible> { +// self.set_high(); +// Ok(()) +// } + +// fn set_low(&mut self) -> Result<(), Infallible> { +// self.set_low(); +// Ok(()) +// } +// } + +// impl StatefulOutputPin for ErasedPin> { +// fn is_set_high(&self) -> Result { +// Ok(self.is_set_high()) +// } + +// fn is_set_low(&self) -> Result { +// Ok(self.is_set_low()) +// } +// } + +// impl InputPin for ErasedPin> { +// type Error = Infallible; +// fn is_high(&self) -> Result { +// Ok(self.is_high()) +// } + +// fn is_low(&self) -> Result { +// Ok(self.is_low()) +// } +// } + +// impl InputPin for ErasedPin> { +// type Error = Infallible; +// fn is_high(&self) -> Result { +// Ok(self.is_high()) +// } + +// fn is_low(&self) -> Result { +// Ok(self.is_low()) +// } +// } diff --git a/src/gpio/hal_1.rs b/src/gpio/hal_1.rs index 6c3344d..25813dc 100644 --- a/src/gpio/hal_1.rs +++ b/src/gpio/hal_1.rs @@ -1,18 +1,9 @@ -use core::convert::Infallible; - use super::{Input, OpenDrain, Output, Pin}; - -//pub use embedded_hal::digital::PinState; +use core::convert::Infallible; use embedded_hal::digital::{ErrorType, InputPin, OutputPin, StatefulOutputPin}; -// fn into_state(state: PinState) -> super::PinState { -// match state { -// PinState::Low => super::PinState::Low, -// PinState::High => super::PinState::High, -// } -// } - // Implementations for `Pin` + impl ErrorType for Pin> { type Error = Infallible; } diff --git a/src/i2c.rs b/src/i2c.rs index 1ea4c82..2245d7d 100644 --- a/src/i2c.rs +++ b/src/i2c.rs @@ -4,12 +4,13 @@ use embedded_hal_02::blocking::i2c::{Read, Write, WriteRead}; use crate::{ gpio::*, - rcc::Rcc, + pac, + rcc::{Clocks, Enable, Reset}, time::{Hertz, KiloHertz, U32Ext}, }; /// I2C abstraction -pub struct I2c { +pub struct I2c { i2c: I2C, pins: (SCLPIN, SDAPIN), } @@ -82,23 +83,38 @@ pub enum Error { PEC, } +// It's s needed for the impls, but rustc doesn't recognize that +#[allow(dead_code)] +type I2cRegisterBlock = crate::pac::i2c::RegisterBlock; + +pub trait Instance: Deref + crate::Sealed + Enable + Reset { + #[doc(hidden)] + fn ptr() -> *const I2cRegisterBlock; +} + macro_rules! i2c { - ($($I2C:ident: ($i2c:ident, $i2cXen:ident, $i2cXrst:ident, $apbenr:ident, $apbrstr:ident),)+) => { + ($($I2C:ident: $i2c:ident,)+) => { $( use crate::pac::$I2C; + impl Instance for $I2C { + fn ptr() -> *const I2cRegisterBlock { + <$I2C>::ptr() + } + } + impl I2c<$I2C, SCLPIN, SDAPIN> { - pub fn $i2c(i2c: $I2C, pins: (SCLPIN, SDAPIN), speed: KiloHertz, rcc: &mut Rcc) -> Self + pub fn $i2c(i2c: $I2C, pins: (SCLPIN, SDAPIN), speed: KiloHertz, clocks: &Clocks) -> Self where SCLPIN: SclPin<$I2C>, SDAPIN: SdaPin<$I2C>, { + let rcc = unsafe { &(*pac::RCC::ptr()) }; // Enable clock for I2C - rcc.regs.$apbenr.modify(|_, w| w.$i2cXen().set_bit()); + $I2C::enable(rcc); // Reset I2C - rcc.regs.$apbrstr.modify(|_, w| w.$i2cXrst().set_bit()); - rcc.regs.$apbrstr.modify(|_, w| w.$i2cXrst().clear_bit()); - I2c { i2c, pins }.i2c_init(rcc.clocks.pclk(), speed) + $I2C::reset(rcc); + I2c { i2c, pins }.i2c_init(clocks.pclk(), speed) } } )+ @@ -106,16 +122,12 @@ macro_rules! i2c { } i2c! { - I2C: (i2c, i2cen, i2crst, apbenr1, apbrstr1), + I2C: i2c, } -// It's s needed for the impls, but rustc doesn't recognize that -#[allow(dead_code)] -type I2cRegisterBlock = crate::pac::i2c::RegisterBlock; - impl I2c where - I2C: Deref, + I2C: Instance, { fn i2c_init(self, freq: Hertz, speed: KiloHertz) -> Self { // Make sure the I2C unit is disabled so we can configure it @@ -219,7 +231,7 @@ where impl WriteRead for I2c where - I2C: Deref, + I2C: Instance, { type Error = Error; @@ -276,7 +288,7 @@ where impl Read for I2c where - I2C: Deref, + I2C: Instance, { type Error = Error; @@ -304,7 +316,7 @@ where impl Write for I2c where - I2C: Deref, + I2C: Instance, { type Error = Error; diff --git a/src/pwm.rs b/src/pwm.rs index ca63c73..e84e2ed 100644 --- a/src/pwm.rs +++ b/src/pwm.rs @@ -1,7 +1,7 @@ use cast::{u16, u32}; use core::{marker::PhantomData, mem::MaybeUninit}; -use crate::rcc::Rcc; +use crate::rcc::{BusTimerClock, Clocks, Enable, Reset}; use crate::time::Hertz; use embedded_hal_02 as hal; @@ -125,17 +125,17 @@ macro_rules! brk { // Timer with four output channels 16 Bit Timer #[cfg(any(feature = "py32f030", feature = "py32f003"))] macro_rules! pwm_4_channels { - ($($TIMX:ident: ($timX:ident, $timXen:ident, $timXrst:ident, $apbenr:ident, $apbrstr:ident),)+) => { + ($($TIMX:ident: $timX:ident,)+) => { $( - pub fn $timX(tim: $TIMX, _pins: PINS, rcc: &mut Rcc, freq: T) -> PINS::Channels + pub fn $timX(tim: $TIMX, _pins: PINS, clocks: &Clocks, freq: T) -> PINS::Channels where PINS: Pins<$TIMX, P>, T: Into, { + let rcc = unsafe { &(*RCC::ptr()) }; // enable and reset peripheral to a clean slate state - rcc.regs.$apbenr.modify(|_, w| w.$timXen().set_bit()); - rcc.regs.$apbrstr.modify(|_, w| w.$timXrst().set_bit()); - rcc.regs.$apbrstr.modify(|_, w| w.$timXrst().clear_bit()); + $TIMX::enable(rcc); + $TIMX::reset(rcc); if PINS::C1 { tim.ccmr1_output() @@ -154,13 +154,7 @@ macro_rules! pwm_4_channels { .modify(|_, w| w.oc4pe().set_bit().oc4m().pwm_mode1() ); } - // If pclk is prescaled from hclk, the frequency fed into the timers is doubled - let tclk = if rcc.clocks.hclk().0 == rcc.clocks.pclk().0 { - rcc.clocks.pclk().0 - } else { - rcc.clocks.pclk().0 * 2 - }; - let ticks = tclk / freq.into().0; + let ticks = $TIMX::timer_clock(clocks).0 / freq.into().0; let psc = u16((ticks - 1) / (1 << 16)).unwrap(); tim.psc.write(|w| unsafe { w.psc().bits(psc) }); @@ -311,17 +305,17 @@ macro_rules! pwm_4_channels { // Timer with four output channels three with complements 16 Bit Timer macro_rules! pwm_4_channels_with_3_complementary_outputs { - ($($TIMX:ident: ($timX:ident, $timXen:ident, $timXrst:ident, $apbenr:ident, $apbrstr:ident),)+) => { + ($($TIMX:ident: $timX:ident,)+) => { $( - pub fn $timX(tim: $TIMX, _pins: PINS, rcc: &mut Rcc, freq: T) -> PINS::Channels + pub fn $timX(tim: $TIMX, _pins: PINS, clocks: &Clocks, freq: T) -> PINS::Channels where PINS: Pins<$TIMX, P>, T: Into, { + let rcc = unsafe { &(*RCC::ptr()) }; // enable and reset peripheral to a clean slate state - rcc.regs.$apbenr.modify(|_, w| w.$timXen().set_bit()); - rcc.regs.$apbrstr.modify(|_, w| w.$timXrst().set_bit()); - rcc.regs.$apbrstr.modify(|_, w| w.$timXrst().clear_bit()); + $TIMX::enable(rcc); + $TIMX::reset(rcc); if PINS::C1N | PINS::C1N | PINS::C1N { tim.bdtr.modify(|_, w| w.ossr().set_bit()); @@ -343,13 +337,7 @@ macro_rules! pwm_4_channels_with_3_complementary_outputs { .modify(|_, w| w.oc4pe().set_bit().oc4m().pwm_mode1() ); } - // If pclk is prescaled from hclk, the frequency fed into the timers is doubled - let tclk = if rcc.clocks.hclk().0 == rcc.clocks.pclk().0 { - rcc.clocks.pclk().0 - } else { - rcc.clocks.pclk().0 * 2 - }; - let ticks = tclk / freq.into().0; + let ticks = $TIMX::timer_clock(clocks).0 / freq.into().0; let psc = u16((ticks - 1) / (1 << 16)).unwrap(); tim.psc.write(|w| unsafe { w.psc().bits(psc) }); @@ -586,18 +574,19 @@ macro_rules! pwm_4_channels_with_3_complementary_outputs { } #[cfg(any(feature = "py32f030", feature = "py32f003"))] +#[allow(unused_macros)] macro_rules! pwm_2_channels { - ($($TIMX:ident: ($timX:ident, $timXen:ident, $timXrst:ident, $apbenr:ident, $apbrstr:ident),)+) => { + ($($TIMX:ident: $timX:ident,)+) => { $( - pub fn $timX(tim: $TIMX, _pins: PINS, rcc: &mut Rcc, freq: T) -> PINS::Channels + pub fn $timX(tim: $TIMX, _pins: PINS, clocks: &Clocks, freq: T) -> PINS::Channels where PINS: Pins<$TIMX, P>, T: Into, { + let rcc = unsafe { &(*RCC::ptr()) }; // enable and reset peripheral to a clean slate state - rcc.regs.$apbenr.modify(|_, w| w.$timXen().set_bit()); - rcc.regs.$apbrstr.modify(|_, w| w.$timXrst().set_bit()); - rcc.regs.$apbrstr.modify(|_, w| w.$timXrst().clear_bit()); + $TIMX::enable(rcc); + $TIMX::reset(rcc); if PINS::C1 { tim.ccmr1_output().modify(|_, w| w.oc1pe().set_bit().oc1m().bits(6)); @@ -606,13 +595,7 @@ macro_rules! pwm_2_channels { tim.ccmr1_output().modify(|_, w| w.oc2pe().set_bit().oc2m().bits(6)); } - // If pclk is prescaled from hclk, the frequency fed into the timers is doubled - let tclk = if rcc.clocks.hclk().0 == rcc.clocks.pclk().0 { - rcc.clocks.pclk().0 - } else { - rcc.clocks.pclk().0 * 2 - }; - let ticks = tclk / freq.into().0; + let ticks = $TIMX::timer_clock(clocks).0 / freq.into().0; let psc = u16((ticks - 1) / (1 << 16)).unwrap(); tim.psc.write(|w| w.psc().bits(psc) ); @@ -702,29 +685,23 @@ macro_rules! pwm_2_channels { // General purpose timer with one output channel (TIM14) #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002b"))] macro_rules! pwm_1_channel { - ($($TIMX:ident: ($timX:ident, $timXen:ident, $timXrst:ident, $apbenr:ident, $apbrstr:ident),)+) => { + ($($TIMX:ident: $timX:ident,)+) => { $( - pub fn $timX(tim: $TIMX, _pins: PINS, rcc: &mut Rcc, freq: T) -> PINS::Channels + pub fn $timX(tim: $TIMX, _pins: PINS, clocks: &Clocks, freq: T) -> PINS::Channels where PINS: Pins<$TIMX, P>, T: Into, { + let rcc = unsafe { &(*RCC::ptr()) }; // enable and reset peripheral to a clean slate state - rcc.regs.$apbenr.modify(|_, w| w.$timXen().set_bit()); - rcc.regs.$apbrstr.modify(|_, w| w.$timXrst().set_bit()); - rcc.regs.$apbrstr.modify(|_, w| w.$timXrst().clear_bit()); + $TIMX::enable(rcc); + $TIMX::reset(rcc); if PINS::C1 { tim.ccmr1_output().modify(|_, w| w.oc1pe().set_bit().oc1m().bits(6)); } - // If pclk is prescaled from hclk, the frequency fed into the timers is doubled - let tclk = if rcc.clocks.hclk().0 == rcc.clocks.pclk().0 { - rcc.clocks.pclk().0 - } else { - rcc.clocks.pclk().0 * 2 - }; - let ticks = tclk / freq.into().0; + let ticks = $TIMX::timer_clock(clocks).0 / freq.into().0; let psc = u16((ticks - 1) / (1 << 16)).unwrap(); tim.psc.write(|w| unsafe { w.psc().bits(psc) }); @@ -783,29 +760,23 @@ macro_rules! pwm_1_channel { // General purpose timer with one output channel (TIM16/TIM17) #[cfg(any(feature = "py32f030", feature = "py32f003"))] macro_rules! pwm_1_channel_with_complementary_outputs { - ($($TIMX:ident: ($timX:ident, $timXen:ident, $timXrst:ident, $apbenr:ident, $apbrstr:ident),)+) => { + ($($TIMX:ident: $timX:ident,)+) => { $( - pub fn $timX(tim: $TIMX, _pins: PINS, rcc: &mut Rcc, freq: T) -> PINS::Channels + pub fn $timX(tim: $TIMX, _pins: PINS, clocks: &Clocks, freq: T) -> PINS::Channels where PINS: Pins<$TIMX, P>, T: Into, { + let rcc = unsafe { &(*RCC::ptr()) }; // enable and reset peripheral to a clean slate state - rcc.regs.$apbenr.modify(|_, w| w.$timXen().set_bit()); - rcc.regs.$apbrstr.modify(|_, w| w.$timXrst().set_bit()); - rcc.regs.$apbrstr.modify(|_, w| w.$timXrst().clear_bit()); + $TIMX::enable(rcc); + $TIMX::reset(rcc); if PINS::C1 { tim.ccmr1_output().modify(|_, w| w.oc1pe().set_bit().oc1m().bits(6)); } - // If pclk is prescaled from hclk, the frequency fed into the timers is doubled - let tclk = if rcc.clocks.hclk().0 == rcc.clocks.pclk().0 { - rcc.clocks.pclk().0 - } else { - rcc.clocks.pclk().0 * 2 - }; - let ticks = tclk / freq.into().0; + let ticks = $TIMX::timer_clock(clocks).0 / freq.into().0; let psc = u16((ticks - 1) / (1 << 16)).unwrap(); tim.psc.write(|w| unsafe { w.psc().bits(psc) }); @@ -866,20 +837,20 @@ macro_rules! pwm_1_channel_with_complementary_outputs { use crate::pac::*; #[cfg(any(feature = "py32f030", feature = "py32f003"))] -pwm_4_channels!(TIM3: (tim3, tim3en, tim3rst, apbenr1, apbrstr1),); +pwm_4_channels!(TIM3: tim3,); -pwm_4_channels_with_3_complementary_outputs!(TIM1: (tim1, tim1en, tim1rst, apbenr2, apbrstr2),); +pwm_4_channels_with_3_complementary_outputs!(TIM1: tim1,); #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002b"))] -pwm_1_channel!(TIM14: (tim14, tim14en, tim14rst, apbenr2, apbrstr2),); +pwm_1_channel!(TIM14: tim14,); // TIM16 is available for all devices but it can not be used for PWM for py32f002a #[cfg(any(feature = "py32f030", feature = "py32f003"))] pwm_1_channel_with_complementary_outputs!( - TIM16: (tim16, tim16en, tim16rst, apbenr2, apbrstr2), + TIM16: tim16, ); #[cfg(any(feature = "py32f030", feature = "py32f003"))] pwm_1_channel_with_complementary_outputs!( - TIM17: (tim17, tim17en, tim17rst, apbenr2, apbrstr2), + TIM17: tim17, ); diff --git a/src/rcc.rs b/src/rcc.rs index 0ca8da0..fd0e6d5 100644 --- a/src/rcc.rs +++ b/src/rcc.rs @@ -414,6 +414,7 @@ impl Clocks { } /// Returns the frequency of the APB Timers + /// If pclk is prescaled from hclk, the frequency fed into the timers is doubled pub const fn pclk_tim(&self) -> Hertz { Hertz(self.pclk.0 * if self.ppre() == 1 { 1 } else { 2 }) } diff --git a/src/spi.rs b/src/spi.rs index 779a1c0..ae98fc7 100644 --- a/src/spi.rs +++ b/src/spi.rs @@ -57,6 +57,7 @@ use crate::time::Hertz; #[cfg(feature = "with-dma")] pub mod dma; +mod hal_02; mod hal_1; /// Clock polarity diff --git a/src/spi/hal_02.rs b/src/spi/hal_02.rs index 2e41015..b09265d 100644 --- a/src/spi/hal_02.rs +++ b/src/spi/hal_02.rs @@ -30,7 +30,7 @@ impl From for super::Mode { } } -impl spi::FullDuplex for Spi +impl spi::FullDuplex for Spi where SPI: Instance, W: Copy, @@ -46,14 +46,17 @@ where } } -impl blocking::transfer::Default for Spi +impl blocking::transfer::Default + for Spi where SPI: Instance, W: Copy, { } -impl blocking::Write for Spi { +impl blocking::Write + for Spi +{ type Error = Error; fn write(&mut self, words: &[u8]) -> Result<(), Error> { @@ -61,7 +64,9 @@ impl blocking::Write for Spi { } } -impl blocking::Write for Spi { +impl blocking::Write + for Spi +{ type Error = Error; fn write(&mut self, words: &[u16]) -> Result<(), Error> { diff --git a/src/timers.rs b/src/timers.rs index 437a788..8acccf7 100644 --- a/src/timers.rs +++ b/src/timers.rs @@ -13,26 +13,24 @@ //! use crate::hal::timers::*; //! use nb::block; //! -//! cortex_m::interrupt::free(|cs| { -//! let mut p = pac::Peripherals::take().unwrap(); -//! let mut rcc = p.RCC.configure().freeze(&mut p.FLASH); +//! let mut p = pac::Peripherals::take().unwrap(); +//! let rcc = p.RCC.configure().freeze(&mut p.FLASH); //! -//! let gpioa = p.GPIOA.split(&mut rcc); +//! let gpioa = p.GPIOA.split(); //! -//! let mut led = gpioa.pa1.into_push_pull_pull_output(cs); +//! let mut led = gpioa.pa1.into_push_pull_pull_output(); //! -//! let mut timer = Timer::tim1(p.TIM1, Hertz(1), &mut rcc); -//! loop { -//! led.toggle(); -//! block!(timer.wait()).ok(); -//! } -//! }); +//! let mut timer = Timer::tim1(p.TIM1, Hertz(1), &rcc.clocks); +//! loop { +//! led.toggle(); +//! block!(timer.wait()).ok(); +//! } //! ``` use cortex_m::peripheral::syst::SystClkSource; use cortex_m::peripheral::SYST; -use crate::rcc::{Clocks, Rcc}; - +use crate::pac::RCC; +use crate::rcc::{BusTimerClock, Clocks, Enable, Rcc, Reset}; use crate::time::Hertz; use embedded_hal_02::timer::{CountDown, Periodic}; use void::Void; @@ -112,8 +110,10 @@ impl CountDown for Timer { impl Periodic for Timer {} +pub trait Instance: crate::Sealed + Enable + Reset + BusTimerClock {} + macro_rules! timers { - ($($TIM:ident: ($tim:ident, $timXen:ident, $timXrst:ident, $apbenr:ident, $apbrstr:ident),)+) => { + ($($TIM:ident: $tim:ident,)+) => { $( use crate::pac::$TIM; impl Timer<$TIM> { @@ -121,17 +121,17 @@ macro_rules! timers { // even if the `$TIM` are non overlapping (compare to the `free` function below // which just works) /// Configures a TIM peripheral as a periodic count down timer - pub fn $tim(tim: $TIM, timeout: T, rcc: &mut Rcc) -> Self + pub fn $tim(tim: $TIM, timeout: T, clocks: &Clocks) -> Self where T: Into, { // enable and reset peripheral to a clean slate state - rcc.regs.$apbenr.modify(|_, w| w.$timXen().set_bit()); - rcc.regs.$apbrstr.modify(|_, w| w.$timXrst().set_bit()); - rcc.regs.$apbrstr.modify(|_, w| w.$timXrst().clear_bit()); + let rcc = unsafe { &(*RCC::ptr()) }; + $TIM::enable(rcc); + $TIM::reset(rcc); let mut timer = Timer { - clocks: rcc.clocks, + clocks: *clocks, tim, }; timer.start(timeout); @@ -165,7 +165,7 @@ macro_rules! timers { // Pause counter self.tim.cr1.modify(|_, w| w.cen().clear_bit()); // Disable timer - rcc.$apbenr.modify(|_, w| w.$timXen().clear_bit()); + $TIM::disable(rcc); self.tim } @@ -189,13 +189,7 @@ macro_rules! timers { self.tim.cnt.reset(); let frequency = timeout.into().0; - // If pclk is prescaled from hclk, the frequency fed into the timers is doubled - let tclk = if self.clocks.hclk().0 == self.clocks.pclk().0 { - self.clocks.pclk().0 - } else { - self.clocks.pclk().0 * 2 - }; - let ticks = tclk / frequency; + let ticks = $TIM::timer_clock(&self.clocks).0 / frequency; let psc = cast::u16((ticks - 1) / (1 << 16)).unwrap(); self.tim.psc.write(|w| unsafe { w.psc().bits(psc) }); @@ -225,23 +219,23 @@ macro_rules! timers { } timers! { - TIM1: (tim1, tim1en, tim1rst, apbenr2, apbrstr2), + TIM1: tim1, } #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] timers! { - TIM16: (tim16, tim16en, tim16rst, apbenr2, apbrstr2), + TIM16: tim16, } #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002b"))] timers! { - TIM14: (tim14, tim14en, tim14rst, apbenr2, apbrstr2), + TIM14: tim14, } #[cfg(any(feature = "py32f030", feature = "py32f003"))] timers! { - TIM3: (tim3, tim3en, tim3rst, apbenr1, apbrstr1), - TIM17: (tim17, tim17en, tim17rst, apbenr2, apbrstr2), + TIM3: tim3, + TIM17: tim17, } use crate::gpio::AF2; From af3dc08e281db9f3667984f3f4827bbd151d3128 Mon Sep 17 00:00:00 2001 From: Greg Green Date: Tue, 26 Nov 2024 13:07:17 -0800 Subject: [PATCH 04/11] Using SpiExt and SerialExt traits to make new instances in examples Fixed docs in mod serial and mod spi --- examples/adc_values.rs | 7 +++---- examples/serial_echo.rs | 3 +-- examples/serial_spi_bridge.rs | 9 +++------ examples/serial_stopwatch.rs | 3 +-- examples/spi_hal_apa102c.rs | 4 +--- examples/spi_rc522.rs | 6 ++---- examples/watchdog.rs | 6 +++--- src/prelude.rs | 4 ++-- src/serial.rs | 6 +++--- src/spi.rs | 4 ++-- 10 files changed, 21 insertions(+), 31 deletions(-) diff --git a/examples/adc_values.rs b/examples/adc_values.rs index dfc1973..35cc374 100644 --- a/examples/adc_values.rs +++ b/examples/adc_values.rs @@ -51,11 +51,10 @@ fn main() -> ! { // USART1 at PA2 (TX) and PA3(RX) let tx = gpioa.pa2.into_alternate_af1(); - let rx = gpioa.pa3.into_alternate_af1(); + let _rx = gpioa.pa3.into_alternate_af1(); // don't need, can be removed - // Initialiase UART - let (mut tx, _) = - hal::serial::Serial::new(dp.USART1, (tx, rx), 115_200.bps(), &rcc.clocks).split(); + // Initialiase UART for transmission only + let mut tx = dp.USART1.tx(tx, 115_200.bps(), &rcc.clocks); // Initialise ADC let adc = hal::adc::Adc::new(dp.ADC, hal::adc::AdcClockMode::default()); diff --git a/examples/serial_echo.rs b/examples/serial_echo.rs index 7cb2642..b8f9416 100644 --- a/examples/serial_echo.rs +++ b/examples/serial_echo.rs @@ -11,7 +11,6 @@ use crate::hal::{ pac, prelude::*, rcc::{HSIFreq, MCODiv, MCOSrc}, - serial::Serial, }; use cortex_m_rt::entry; @@ -37,7 +36,7 @@ fn main() -> ! { gpioa.pa3.into_alternate_af1(), ); - let mut serial = Serial::new(p.USART1, (tx, rx), 115_200.bps(), &rcc.clocks); + let mut serial = p.USART1.serial((tx, rx), 115_200.bps(), &rcc.clocks); serial.write_str("Input any key:\n").ok(); loop { diff --git a/examples/serial_spi_bridge.rs b/examples/serial_spi_bridge.rs index 46d1278..b2c5893 100644 --- a/examples/serial_spi_bridge.rs +++ b/examples/serial_spi_bridge.rs @@ -8,8 +8,6 @@ use py32f0xx_hal as hal; use crate::hal::{ pac, prelude::*, - serial::Serial, - spi::Spi, spi::{Mode, Phase, Polarity}, }; @@ -48,15 +46,14 @@ fn main() -> ! { ); // Configure SPI with 1MHz rate - let mut spi = Spi::new( - p.SPI1, + let mut spi = p.SPI1.spi( (Some(sck), Some(miso), Some(mosi)), MODE, - 1.mhz(), + 1.mhz().into(), &rcc.clocks, ); - let mut serial = Serial::new(p.USART1, (tx, rx), 115_200.bps(), &rcc.clocks); + let mut serial = p.USART1.serial((tx, rx), 115_200.bps(), &rcc.clocks); let mut datatx = [0]; let datarx = [0]; diff --git a/examples/serial_stopwatch.rs b/examples/serial_stopwatch.rs index bb1278a..5b281c5 100644 --- a/examples/serial_stopwatch.rs +++ b/examples/serial_stopwatch.rs @@ -8,7 +8,6 @@ use py32f0xx_hal as hal; use crate::hal::{ pac::{interrupt, Interrupt, Peripherals, TIM16}, prelude::*, - serial::Serial, timers::{Event, Timer}, }; use core::cell::RefCell; @@ -84,7 +83,7 @@ fn main() -> ! { cortex_m::peripheral::NVIC::unpend(Interrupt::TIM16); // Set up our serial port - Serial::new(p.USART1, (tx, rx), 115_200.bps(), &rcc.clocks) + p.USART1.serial((tx, rx), 115_200.bps(), &rcc.clocks) }); // Print a welcome message diff --git a/examples/spi_hal_apa102c.rs b/examples/spi_hal_apa102c.rs index 6725a16..ba98d1c 100644 --- a/examples/spi_hal_apa102c.rs +++ b/examples/spi_hal_apa102c.rs @@ -8,7 +8,6 @@ use py32f0xx_hal as hal; use crate::hal::{ pac, prelude::*, - spi::Spi, spi::{Mode, Phase, Polarity}, }; @@ -35,8 +34,7 @@ fn main() -> ! { ); // Configure SPI with 100kHz rate - let mut spi = Spi::new( - p.SPI1, + let mut spi = p.SPI1.spi( (Some(sck), Some(miso), Some(mosi)), MODE, 100_000.hz(), diff --git a/examples/spi_rc522.rs b/examples/spi_rc522.rs index d8d910c..8060118 100644 --- a/examples/spi_rc522.rs +++ b/examples/spi_rc522.rs @@ -10,7 +10,6 @@ use crate::hal::{ delay::Delay, pac, prelude::*, - spi::Spi, spi::{Mode, Phase, Polarity}, time::Hertz, timers::Timer, @@ -60,11 +59,10 @@ fn main() -> ! { rst.set_low().ok(); // Configure SPI with 1MHz rate - let spi = Spi::new( - p.SPI1, + let spi = p.SPI1.spi( (Some(sck), Some(miso), Some(mosi)), MODE, - 1.mhz(), + 1.mhz().into(), &rcc.clocks, ); let itf = SpiInterface::new(spi).with_nss(nss).with_delay(|| { diff --git a/examples/watchdog.rs b/examples/watchdog.rs index df9dca8..c5e85be 100644 --- a/examples/watchdog.rs +++ b/examples/watchdog.rs @@ -5,7 +5,7 @@ use panic_halt as _; use py32f0xx_hal as hal; -use crate::hal::{delay::Delay, pac, prelude::*, serial::Serial, time::Hertz, watchdog}; +use crate::hal::{delay::Delay, pac, prelude::*, time::Hertz, watchdog}; use core::fmt::Write; use cortex_m::peripheral::Peripherals; use cortex_m_rt::entry; @@ -32,8 +32,8 @@ fn main() -> ! { // Configure serial TX pin let tx = gpioa.pa2.into_alternate_af1(); - // Obtain a serial peripheral with for unidirectional communication - let mut serial = Serial::new(p.USART1, (tx, ()), 115_200.bps(), &rcc.clocks); + // Obtain a serial peripheral with unidirectional communication + let mut serial = p.USART1.tx(tx, 115_200.bps(), &rcc.clocks); serial.write_str("RESET \r\n").ok(); diff --git a/src/prelude.rs b/src/prelude.rs index 6d11561..428089c 100644 --- a/src/prelude.rs +++ b/src/prelude.rs @@ -10,6 +10,6 @@ pub use crate::dma::ReadWriteDma as _py32f0xx_hal_dma_ReadWriteDma; pub use crate::dma::WriteDma as _py32f0xx_hal_dma_WriteDma; pub use crate::gpio::GpioExt as _py32f0xx_hal_gpio_GpioExt; pub use crate::rcc::RccExt as _py32f0xx_hal_rcc_RccExt; -pub use crate::serial::SerialExt as _; -pub use crate::spi::SpiExt as _; +pub use crate::serial::SerialExt as _py32f0xx_hal_serial_SerialExt; +pub use crate::spi::SpiExt as _py32f0xx_hal_spi_SpiExt; pub use crate::time::U32Ext as _py32f0xx_hal_time_U32Ext; diff --git a/src/serial.rs b/src/serial.rs index a99594d..216d253 100644 --- a/src/serial.rs +++ b/src/serial.rs @@ -3,7 +3,7 @@ //! This only implements the usual asynchronous bidirectional 8-bit transfers. //! //! It's possible to use a read-only/write-only serial implementation with -//! `usartXrx`/`usartXtx`. +//! `rx`/`tx`. //! //! # Examples //! Echo @@ -25,7 +25,7 @@ //! let rx = gpiob.pb7.into_alternate_af0(); //! //! // Create an interface struct for USART1 with 115200 Baud -//! let mut serial = Serial::new(p.USART1, (tx, rx), 115_200.bps(), &rcc.clocks); +//! let mut serial = p.USART1.serial((tx, rx), 115_200.bps(), &rcc.clocks); //! //! loop { //! let received = block!(serial.read()).unwrap(); @@ -49,7 +49,7 @@ //! //! let tx = gpiob.pb6.into_alternate_af0(); //! -//! let mut serial = Serial::new(p.USART1, tx, 115_200.bps(), &rcc.clocks); +//! let mut serial = p.USART1.tx(tx, 115_200.bps(), &rcc.clocks); //! //! loop { //! serial.write_str("Hello World!\r\n"); diff --git a/src/spi.rs b/src/spi.rs index ae98fc7..7261709 100644 --- a/src/spi.rs +++ b/src/spi.rs @@ -17,7 +17,7 @@ //! use embedded_hal::spi::SpiBus; //! //! let mut p = pac::Peripherals::take().unwrap(); -//! let mut rcc = p.RCC.constrain().freeze(&mut p.FLASH); +//! let rcc = p.RCC.constrain().freeze(&mut p.FLASH); //! //! let gpioa = p.GPIOA.split(&mut rcc); //! @@ -27,7 +27,7 @@ //! let mosi = gpioa.pa7.into_alternate_af0(); //! //! // Configure SPI with 1MHz rate -//! let mut spi = Spi::new(p.SPI1, (Some(sck), Some(miso), Some(mosi)), Mode { +//! let mut spi = p.SPI1.spi((Some(sck), Some(miso), Some(mosi)), Mode { //! polarity: Polarity::IdleHigh, //! phase: Phase::CaptureOnSecondTransition, //! }, 1.mhz(), &rcc.clocks); From b4ac61cf4f427d9571e94e275d35c30212cd17ba Mon Sep 17 00:00:00 2001 From: Greg Green Date: Thu, 28 Nov 2024 14:16:28 -0800 Subject: [PATCH 05/11] Added exti example Fixed typo in adc_values example Added listen/unlisten to dma Transfers so interrupts can be used Removed unused parameter in gpio! macro --- examples/adc_values.rs | 4 +-- examples/exti.rs | 65 ++++++++++++++++++++++++++++++++++++++++++ src/dma.rs | 36 +++++++++++++++++++++++ src/gpio.rs | 10 +++---- 4 files changed, 108 insertions(+), 7 deletions(-) create mode 100644 examples/exti.rs diff --git a/examples/adc_values.rs b/examples/adc_values.rs index 35cc374..6897f9a 100644 --- a/examples/adc_values.rs +++ b/examples/adc_values.rs @@ -94,12 +94,12 @@ fn SysTick() { writeln!(shared.tx, "Temperature {}.{}C\r", t / 100, t % 100).ok(); info!("Temperature {}.{}C\r", t / 100, t % 100); - // Read volatage reference data from internal sensor using ADC + // Read voltage reference data from internal sensor using ADC let t = hal::adc::VRef::read_vdda(&mut shared.adc); writeln!(shared.tx, "Vdda {}mV\r", t).ok(); info!("Vdda {}mV\r", t); - // Read volatage data from external pin using ADC + // Read voltage data from external pin using ADC let v0 = hal::adc::Adc::read_abs_mv(&mut shared.adc, &mut shared.ain0); let v1 = hal::adc::Adc::read_abs_mv(&mut shared.adc, &mut shared.ain1); writeln!(shared.tx, "Ain0 {}mV Ain1 {}mV\r", v0, v1).ok(); diff --git a/examples/exti.rs b/examples/exti.rs new file mode 100644 index 0000000..74df95a --- /dev/null +++ b/examples/exti.rs @@ -0,0 +1,65 @@ +//! Turns the user LED on +//! +//! Listens for interrupts on the pa11 pin. On any rising or falling edge, toggles +//! the pa12 pin (which is connected to the LED on the dev board, hence the `led` name). + +#![allow(clippy::empty_loop)] +#![no_main] +#![no_std] + +use panic_halt as _; + +use core::mem::MaybeUninit; +use cortex_m_rt::entry; +use pac::interrupt; +use py32f0xx_hal::gpio::*; +use py32f0xx_hal::{pac, prelude::*}; + +// These two are owned by the ISR. main() may only access them during the initialization phase, +// where the interrupt is not yet enabled (i.e. no concurrent accesses can occur). +// After enabling the interrupt, main() may not have any references to these objects any more. +// For the sake of minimalism, we do not use RTIC here, which would be the better way. +static mut LED: MaybeUninit>> = + MaybeUninit::uninit(); +static mut INT_PIN: MaybeUninit>> = MaybeUninit::uninit(); + +#[interrupt] +fn EXTI4_15() { + let led = unsafe { &mut *LED.as_mut_ptr() }; + let int_pin = unsafe { &mut *INT_PIN.as_mut_ptr() }; + + if int_pin.check_interrupt() { + led.toggle(); + + // if we don't clear this bit, the ISR would trigger indefinitely + int_pin.clear_interrupt_pending_bit(); + } +} + +#[entry] +fn main() -> ! { + // initialization phase + let mut p = pac::Peripherals::take().unwrap(); + let _cp = cortex_m::peripheral::Peripherals::take().unwrap(); + let _rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); + { + // the scope ensures that the int_pin reference is dropped before the first ISR can be executed. + + let gpioa = p.GPIOA.split(); + + let led = unsafe { &mut *LED.as_mut_ptr() }; + *led = gpioa.pa12.into_push_pull_output(); + + let int_pin = unsafe { &mut *INT_PIN.as_mut_ptr() }; + *int_pin = gpioa.pa11.into_floating_input().downgrade(); + int_pin.make_interrupt_source(&mut p.EXTI); + int_pin.trigger_on_edge(&mut p.EXTI, Edge::RisingFalling); + int_pin.enable_interrupt(&mut p.EXTI); + } // initialization ends here + + unsafe { + pac::NVIC::unmask(pac::Interrupt::EXTI4_15); + } + + loop {} +} diff --git a/src/dma.rs b/src/dma.rs index a8e89b0..5f7a98b 100644 --- a/src/dma.rs +++ b/src/dma.rs @@ -424,10 +424,22 @@ impl where RxDma>: TransferPayload, { + /// Is the Transfer completed pub fn is_done(&self) -> bool { !self.payload.channel.in_progress() } + /// Listen for Events on DMA channel + pub fn listen(&mut self, evt: Event) { + self.payload.channel.listen(evt); + } + + /// Unlisten for Events on DMA channel + pub fn unlisten(&mut self, evt: Event) { + self.payload.channel.unlisten(evt); + } + + /// Wait until Transfer is completed, blocking pub fn wait(mut self) -> (BUFFER, RxDma>) { while !self.is_done() {} @@ -465,10 +477,22 @@ impl where TxDma>: TransferPayload, { + /// Is the Transfer completed pub fn is_done(&self) -> bool { !self.payload.channel.in_progress() } + /// Listen for Events on DMA channel + pub fn listen(&mut self, evt: Event) { + self.payload.channel.listen(evt); + } + + /// Unlisten for Events on DMA channel + pub fn unlisten(&mut self, evt: Event) { + self.payload.channel.unlisten(evt); + } + + /// Wait until Transfer is completed, blocking pub fn wait(mut self) -> (BUFFER, TxDma>) { while !self.is_done() {} @@ -506,10 +530,22 @@ impl where RxTxDma, Ch>: TransferPayload, { + /// Is the Transfer completed pub fn is_done(&self) -> bool { !self.payload.rxchannel.in_progress() } + /// Listen for Events on DMA rx channel + pub fn listen_rx(&mut self, evt: Event) { + self.payload.rxchannel.listen(evt); + } + + /// Unlisten for Events on DMA rx channel + pub fn unlisten_rx(&mut self, evt: Event) { + self.payload.rxchannel.unlisten(evt); + } + + /// Wait until Transfer is completed, blocking pub fn wait(mut self) -> (BUFFER, RxTxDma, Ch>) { while !self.is_done() {} diff --git a/src/gpio.rs b/src/gpio.rs index dbcb849..2faeb46 100644 --- a/src/gpio.rs +++ b/src/gpio.rs @@ -304,7 +304,7 @@ gpio_trait!(gpiof); gpio_trait!(gpioc); macro_rules! gpio { - ([$($GPIOX:ident, $gpiox:ident, $PXx:ident, $PCH:literal, $gate:meta => [ + ([$($GPIOX:ident, $gpiox:ident, $PCH:literal, $gate:meta => [ $($PXi:ident: ($pxi:ident, $i:expr, $MODE:ty),)+ ]),+]) => { $( @@ -781,7 +781,7 @@ macro_rules! gpio { gpio!([ // BUGBUG: py32f002b only has 8 pins? - GPIOA, gpioa, PA, b'A', any( + GPIOA, gpioa, b'A', any( feature = "device-selected" ) => [ PA0: (pa0, 0, Input), @@ -801,7 +801,7 @@ gpio!([ PA14: (pa14, 14, Input), PA15: (pa15, 15, Input), ], - GPIOB, gpiob, PB, b'B', any( + GPIOB, gpiob, b'B', any( feature = "device-selected" ) => [ PB0: (pb0, 0, Input), @@ -814,13 +814,13 @@ gpio!([ PB7: (pb7, 7, Input), PB8: (pb8, 8, Input), ], - GPIOC, gpioc, PC, b'C', any( + GPIOC, gpioc, b'C', any( feature = "py32f002b" ) => [ PC0: (pf0, 0, Input), PC1: (pf1, 1, Input), ], - GPIOF, gpiof, PF, b'F', any( + GPIOF, gpiof, b'F', any( feature = "py32f030", feature = "py32f003", feature = "py32f002a" From c3b339ef47df8ca1618e1a5ff489c7246ce0d859 Mon Sep 17 00:00:00 2001 From: Greg Green Date: Mon, 2 Dec 2024 11:12:11 -0800 Subject: [PATCH 06/11] Overhauled gpio to have PartialErasedPin and ErasedPin Filled out CHANGELOG.md Altered examples to use changed gpio module Added module rtc and 2 examples Added 'disable_dbg' method to Rcc --- CHANGELOG.md | 79 +- examples/blinky_adc.rs | 5 +- examples/blinky_delay.rs | 5 +- examples/blinky_multiple.rs | 7 +- examples/blinky_rtc.rs | 43 + examples/blinky_timer.rs | 5 +- examples/blinky_timer_irq.rs | 9 +- examples/exti.rs | 5 +- examples/spi_rc522.rs | 9 +- src/adc.rs | 9 +- src/gpio.rs | 1624 +++++++++++++++++++++------------- src/gpio/erased.rs | 130 +++ src/gpio/hal_02.rs | 272 +++--- src/gpio/hal_1.rs | 294 +++--- src/gpio/partially_erased.rs | 117 +++ src/lib.rs | 2 + src/rcc.rs | 7 +- src/rcc/enable.rs | 4 +- src/rtc.rs | 399 +++++++++ src/serial.rs | 8 +- src/spi.rs | 3 +- 21 files changed, 2134 insertions(+), 902 deletions(-) create mode 100644 examples/blinky_rtc.rs create mode 100644 src/gpio/erased.rs create mode 100644 src/gpio/partially_erased.rs create mode 100644 src/rtc.rs diff --git a/CHANGELOG.md b/CHANGELOG.md index 662b48b..159a730 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -2,6 +2,83 @@ All notable changes to this project will be documented in this file. +## Unreleased + +This version depends on py32-rs v1.1.2 or later + +### Added + +- added module `dma` +- added feature gate to select "with-dma" +- module `gpio` has the following new types and traits: + * Struct `PartiallyErasedPin` and `ErasedPin` replaces previous `Pin` + * Struct `DynamicPin` allows pin to swap between an `Input` and `Output` pin during runtime at the cost of possible runtime errors + * Trait `ExtiPin` allows connecting a pin to EXTI lines for interrupt and event handling + * Trait `Debugger` marks pins that upon bootup are dedicated to the DBG peripheral, must be `activate` before use as a gpio + * Trait `PinExt` adds functions to retrieve pin number and port id ('A', 'B', etc) +- gpio Pins can be temporarily mode changed to do an action, using these methods: + * `as_push_pull_output` + * `as_push_pull_output_with_state` + * `as_open_drain_output` + * `as_open_drain_output_with_state` + * `as_floating_input` + * `as_pull_up_input` + * `as_pull_down_input` +- module `rcc` has new traits and implementations `Enable`, `Reset`, `BusClock`, `BusTimerClock`, `RccBus` +- added module `rtc` and examples thereof +- module `serial` + * Implemented embedded-hal v1.0 nb::Read/Write traits + * Implemented embedded-hal v1.0 io::Write trait + * Implemented `with_dma` methods, so Rx/Tx can use DMA + * Added `SerialExt` trait and implementations for construction methods + * Can configure stop bits, parity, word length + * added `reconfigure` +- module `spi` + * Implemented embedded-hal v1.0 SpiBus, nb, and blocking, traits + * Implemented `with_dma` methods, both Rx/Tx can use DMA, separately and together + * Added `SpiExt` trait and implementations for construction methods + * Works with both 8 and 16 bit words, though 16bit not tested + * Added `SpiSlave` for slave functionality, though it is not tested + * Added frame size conversion methods, [ex: `frame_size_8_bit`] + +### Changed + +- Changed all examples to use new api's where necessary +- module `adc` changed to use new rcc enable, reset, and bus frequencies +- module `gpio` + * pin `into_` fns have removed the atomic context parameter which is not needed depending on what OS is used + * implemented `split_without_reset` + * Pin type doesn't represent an erased pin, but the most specific type of pin, see Added above + * embedded-hal v0.2.7 traits moved to gpio/hal_02 module +- module `i2c` changed to use rcc enable, reset, and bus frequencies +- module `prelude` removed all embedded-hal traits +- module `pwm` changed to use rcc enable, reset, and bus frequencies +- module `serial` + * embedded-hal v0.2.7 trait implementations moved to serial/hal_02 module + * changed to use rcc enable, reset, and bus frequencies +- module `spi` + * embedded-hal v0.2.7 trait implementations moved to spi/hal_02 module + * changed to use rcc enable, reset, and bus frequencies +- module `timers` + * changed to use rcc enable, reset, and bus frequencies + +### Deprecated + +### Removed + +- `spi::Event::Crc` removed, as that doesn't exist on this micro + +### Fixed + +### Security + +## v0.1.1 + +## V0.1.0 + +## v0.0.1 + + - Original Release + The format is based on [Keep a Changelog](http://keepachangelog.com/) and this project adheres to [Semantic Versioning](http://semver.org/). - diff --git a/examples/blinky_adc.rs b/examples/blinky_adc.rs index 4203107..f3f48fb 100644 --- a/examples/blinky_adc.rs +++ b/examples/blinky_adc.rs @@ -11,7 +11,6 @@ use cortex_m::peripheral::Peripherals; use cortex_m_rt::entry; use embedded_hal_02::adc::OneShot; use embedded_hal_02::blocking::delay::DelayMs; -use embedded_hal_02::digital::v2::ToggleableOutputPin; #[entry] fn main() -> ! { @@ -21,7 +20,7 @@ fn main() -> ! { let gpioa = p.GPIOA.split(); // (Re-)configure PA5 as output - let mut led = gpioa.pa5.into_push_pull_output().downgrade(); + let mut led = gpioa.pa5.into_push_pull_output(); // (Re-)configure PA0 as analog input let mut an_in = gpioa.pa0.into_analog(); @@ -32,7 +31,7 @@ fn main() -> ! { let mut adc = Adc::new(p.ADC, hal::adc::AdcClockMode::Pclk); loop { - led.toggle().ok(); + led.toggle(); let time: u16 = if let Ok(val) = adc.read(&mut an_in) as Result { /* shift the value right by 3, same as divide by 8, reduces diff --git a/examples/blinky_delay.rs b/examples/blinky_delay.rs index af64525..49ead16 100644 --- a/examples/blinky_delay.rs +++ b/examples/blinky_delay.rs @@ -9,7 +9,6 @@ use crate::hal::{delay::Delay, pac, prelude::*}; use cortex_m::peripheral::Peripherals; use cortex_m_rt::entry; use embedded_hal_02::blocking::delay::DelayMs; -use embedded_hal_02::digital::v2::ToggleableOutputPin; #[entry] fn main() -> ! { @@ -19,13 +18,13 @@ fn main() -> ! { let gpioa = p.GPIOA.split(); // (Re-)configure PA5 as output - let mut led = gpioa.pa5.into_push_pull_output().downgrade(); + let mut led = gpioa.pa5.into_push_pull_output(); // Get delay provider let mut delay = Delay::new(cp.SYST, &rcc); loop { - led.toggle().ok(); + led.toggle(); delay.delay_ms(1_000_u16); } } diff --git a/examples/blinky_multiple.rs b/examples/blinky_multiple.rs index fde11a4..d7ec248 100644 --- a/examples/blinky_multiple.rs +++ b/examples/blinky_multiple.rs @@ -9,7 +9,6 @@ use crate::hal::{delay::Delay, pac, prelude::*}; use cortex_m::peripheral::Peripherals; use cortex_m_rt::entry; -use embedded_hal::digital::OutputPin; use embedded_hal_02::blocking::delay::DelayMs; #[entry] @@ -29,15 +28,15 @@ fn main() -> ! { let mut delay = Delay::new(cp.SYST, &rcc); // Store them together after erasing the type - let mut leds = [led1.downgrade(), led2.downgrade()]; + let mut leds = [led1.erase(), led2.erase()]; loop { for l in &mut leds { - l.set_high().ok(); + l.set_high(); } delay.delay_ms(1_000_u16); for l in &mut leds { - l.set_low().ok(); + l.set_low(); } delay.delay_ms(1_000_u16); } diff --git a/examples/blinky_rtc.rs b/examples/blinky_rtc.rs new file mode 100644 index 0000000..b1b5686 --- /dev/null +++ b/examples/blinky_rtc.rs @@ -0,0 +1,43 @@ +//! Blinks an LED +//! +//! This assumes that a LED is connected to pa12 + +#![deny(unsafe_code)] +#![no_std] +#![no_main] + +use panic_halt as _; + +use py32f0xx_hal::{pac, prelude::*, rtc::Rtc}; + +use cortex_m_rt::entry; +use nb::block; + +#[entry] +fn main() -> ! { + let dp = pac::Peripherals::take().unwrap(); + + // Set up the GPIO pin + let gpioa = dp.GPIOA.split(); + let mut led = gpioa.pa12.into_push_pull_output(); + + // Set up the RTC + // Start the RTC + let mut rtc = Rtc::new(dp.RTC); + + let mut led_on = false; + loop { + // Set the current time to 0 + rtc.set_time(0); + // Trigger the alarm in 5 seconds + rtc.set_alarm(5); + block!(rtc.wait_alarm()).unwrap(); + if led_on { + led.set_low(); + led_on = false; + } else { + led.set_high(); + led_on = true; + } + } +} diff --git a/examples/blinky_timer.rs b/examples/blinky_timer.rs index ab4fbd8..cd1cc2d 100644 --- a/examples/blinky_timer.rs +++ b/examples/blinky_timer.rs @@ -9,7 +9,6 @@ use crate::hal::{pac, prelude::*, time::Hertz, timers::*}; use cortex_m_rt::entry; -use embedded_hal_02::digital::v2::ToggleableOutputPin; use embedded_hal_02::timer::CountDown; #[entry] @@ -20,13 +19,13 @@ fn main() -> ! { let gpioa = p.GPIOA.split(); // (Re-)configure PA5 as output - let mut led = gpioa.pa5.into_push_pull_output().downgrade(); + let mut led = gpioa.pa5.into_push_pull_output(); // Set up a timer expiring after 1s let mut timer = Timer::tim1(p.TIM1, Hertz(5), &rcc.clocks); loop { - led.toggle().ok(); + led.toggle(); // Wait for the timer to expire nb::block!(timer.wait()).ok(); diff --git a/examples/blinky_timer_irq.rs b/examples/blinky_timer_irq.rs index 93cf182..6c56087 100644 --- a/examples/blinky_timer_irq.rs +++ b/examples/blinky_timer_irq.rs @@ -6,7 +6,7 @@ use panic_halt as _; use py32f0xx_hal as hal; use crate::hal::{ - gpio::{Output, Pin, PushPull}, + gpio::{gpioa, Output, PushPull}, pac::{interrupt, Interrupt, Peripherals, TIM16}, prelude::*, time::Hertz, @@ -16,11 +16,10 @@ use crate::hal::{ use core::cell::RefCell; use cortex_m::{interrupt::Mutex, peripheral::Peripherals as c_m_Peripherals}; use cortex_m_rt::entry; -use embedded_hal_02::digital::v2::ToggleableOutputPin; use embedded_hal_02::timer::CountDown; // A type definition for the GPIO pin to be used for our LED -type LEDPIN = Pin>; +type LEDPIN = gpioa::PA5>; // Make LED pin globally available static GLED: Mutex>> = Mutex::new(RefCell::new(None)); @@ -49,7 +48,7 @@ fn TIM16() { }) }); - led.toggle().ok(); + led.toggle(); int.wait().ok(); } @@ -67,7 +66,7 @@ fn main() -> ! { let gpioa = p.GPIOA.split(); // (Re-)configure PA5 as output - let led = gpioa.pa5.into_push_pull_output().downgrade(); + let led = gpioa.pa5.into_push_pull_output(); // Move the pin into our global storage *GLED.borrow(cs).borrow_mut() = Some(led); diff --git a/examples/exti.rs b/examples/exti.rs index 74df95a..b1adb42 100644 --- a/examples/exti.rs +++ b/examples/exti.rs @@ -21,7 +21,8 @@ use py32f0xx_hal::{pac, prelude::*}; // For the sake of minimalism, we do not use RTIC here, which would be the better way. static mut LED: MaybeUninit>> = MaybeUninit::uninit(); -static mut INT_PIN: MaybeUninit>> = MaybeUninit::uninit(); +static mut INT_PIN: MaybeUninit>> = + MaybeUninit::uninit(); #[interrupt] fn EXTI4_15() { @@ -51,7 +52,7 @@ fn main() -> ! { *led = gpioa.pa12.into_push_pull_output(); let int_pin = unsafe { &mut *INT_PIN.as_mut_ptr() }; - *int_pin = gpioa.pa11.into_floating_input().downgrade(); + *int_pin = gpioa.pa11.into_floating_input(); int_pin.make_interrupt_source(&mut p.EXTI); int_pin.trigger_on_edge(&mut p.EXTI, Edge::RisingFalling); int_pin.enable_interrupt(&mut p.EXTI); diff --git a/examples/spi_rc522.rs b/examples/spi_rc522.rs index 8060118..cf07963 100644 --- a/examples/spi_rc522.rs +++ b/examples/spi_rc522.rs @@ -17,7 +17,6 @@ use crate::hal::{ use cortex_m_rt::entry; use defmt::{error, info}; use embedded_hal_02::blocking::delay::DelayMs; -use embedded_hal_02::digital::v2::OutputPin; use embedded_hal_02::timer::CountDown; use mfrc522::comm::eh02::spi::SpiInterface; @@ -53,10 +52,10 @@ fn main() -> ! { gpioa.pa6.into_alternate_af0(), gpioa.pa7.into_alternate_af0(), // Aux pins - gpioa.pa4.into_push_pull_output().downgrade(), - gpioa.pa1.into_push_pull_output().downgrade(), + gpioa.pa4.into_push_pull_output(), + gpioa.pa1.into_push_pull_output(), ); - rst.set_low().ok(); + rst.set_low(); // Configure SPI with 1MHz rate let spi = p.SPI1.spi( @@ -68,7 +67,7 @@ fn main() -> ! { let itf = SpiInterface::new(spi).with_nss(nss).with_delay(|| { delay.delay_ms(1_u16); }); - rst.set_high().ok(); + rst.set_high(); let mut mfrc522 = Mfrc522::new(itf).init().unwrap(); diff --git a/src/adc.rs b/src/adc.rs index 5ccb4ce..711c059 100644 --- a/src/adc.rs +++ b/src/adc.rs @@ -501,7 +501,8 @@ impl Adc { } while self.rb.cr.read().aden().is_enabled() {} - #[cfg(any(feature = "py32f030", feature = "py32f003"))] + // get and save DMAEN and DMACFG + #[cfg(feature = "with-dma")] let (dmacfg, dmaen) = { let dmacfg = self.rb.cfgr1.read().dmacfg().bit(); let dmaen = self.rb.cfgr1.read().dmaen().is_enabled(); @@ -510,7 +511,8 @@ impl Adc { }; /* Clear DMAEN */ - // self.rb.cfgr1.modify(|_, w| w.dmaen().disabled()); + #[cfg(feature = "with-dma")] + self.rb.cfgr1.modify(|_, w| w.dmaen().disabled()); /* Start calibration by setting ADCAL */ self.rb.cr.modify(|_, w| w.adcal().start_calibration()); @@ -518,7 +520,8 @@ impl Adc { /* Wait until calibration is finished and ADCAL = 0 */ while self.rb.cr.read().adcal().is_calibrating() {} - #[cfg(any(feature = "py32f030", feature = "py32f003"))] + // restore DMAEN and DMACFG to original values + #[cfg(feature = "with-dma")] self.rb .cfgr1 .modify(|_, w| w.dmacfg().bit(dmacfg).dmaen().bit(dmaen)); diff --git a/src/gpio.rs b/src/gpio.rs index 2faeb46..c27b2df 100644 --- a/src/gpio.rs +++ b/src/gpio.rs @@ -1,8 +1,73 @@ -//! General Purpose Input / Output +//! # General Purpose I/Os +//! +//! The GPIO pins are organised into groups of 16 pins which can be accessed through the +//! `gpioa`, `gpiob`... modules. To get access to the pins, you first need to convert them into a +//! HAL designed struct from the `pac` struct using the [split](trait.GpioExt.html#tymethod.split) function. +//! ```rust +//! // Acquire the GPIOA peripheral +//! // NOTE: `dp` is the device peripherals from the `PAC` crate +//! let mut gpioa = dp.GPIOA.split(); +//! ``` +//! +//! This gives you a struct containing all the pins `px0..px15`. These +//! structs are what you use to interract with the pins to change +//! their modes, or their inputs or outputs. For example, to set `pa5` +//! high, you would call +//! +//! ```rust +//! let output = gpioa.pa5.into_push_pull_output(); +//! output.set_high(); +//! ``` +//! +//! ## Modes +//! +//! Each GPIO pin can be set to various modes: +//! +//! - **Alternate**: Pin mode required when the pin is driven by other peripherals +//! - **Dynamic**: Pin mode is selected at runtime. See changing configurations for more details +//! - Input +//! - **PullUp**: Input connected to high with a weak pull-up resistor. Will be high when nothing +//! is connected +//! - **PullDown**: Input connected to ground with a weak pull-down resistor. Will be low when nothing +//! is connected +//! - **Floating**: Input not pulled to high or low. Will be undefined when nothing is connected +//! - Output +//! - **PushPull**: Output which either drives the pin high or low +//! - **OpenDrain**: Output which leaves the gate floating, or pulls it to ground in drain +//! mode. Can be used as an input in the `open` configuration +//! - **Debugger**: Some pins start out being used by the debugger. A pin in this mode can only be +//! used if the [JTAG peripheral has been turned off](#accessing-pa13-and-pa14). +//! +//! ## Changing modes +//! The simplest way to change the pin mode is to use the `into_` functions. These return a +//! new struct with the correct mode that you can use the input or output functions on. +//! +//! If you need a more temporary mode change, and can not use the `into_` functions for +//! ownership reasons, you can use the `as_` functions to temporarily change the pin type, do +//! some output or input, and then have it change back once done. +//! +//! ### Dynamic Mode Change +//! The above mode change methods guarantee that you can only call input functions when the pin is +//! in input mode, and output when in output modes, but can lead to some issues. Therefore, there +//! is also a mode where the state is kept track of at runtime, allowing you to change the mode +//! often, and without problems with ownership, or references, at the cost of some performance and +//! the risk of runtime errors. +//! +//! To make a pin dynamic, use the `into_dynamic` function, and then use the `make_` functions to +//! change the mode +//! +//! ## Accessing PA13, and PA14 +//! +//! These pins are used by the DBG peripheral by default. To use them in your program, you need to +//! disable that peripheral. This is done using the [rcc::APB::disable_dbg](../rcc/struct.APB.html#method.disable_dbg) function +use crate::pac; use core::marker::PhantomData; -use crate::pac; +mod erased; +pub use erased::{AnyPin, ErasedPin}; +mod partially_erased; +pub use partially_erased::{PEPin, PartiallyErasedPin}; mod hal_02; mod hal_1; @@ -13,7 +78,9 @@ pub trait PinExt { /// Return pin number fn pin_id(&self) -> u8; - /// Return port + /// Return port id + /// + /// id is a character, such as 'A' for porta, 'B' for portb fn port_id(&self) -> u8; } @@ -34,12 +101,108 @@ pub trait GpioExt { unsafe fn split_without_reset(self) -> Self::Parts; } -trait GpioRegExt { - fn is_low(&self, pos: u8) -> bool; - fn is_set_low(&self, pos: u8) -> bool; - fn set_high(&self, pos: u8); - fn set_low(&self, pos: u8); -} +/// Marker trait for active states. +pub trait Active {} + +/// Input mode (type state) +#[derive(Default)] +pub struct Input(PhantomData); + +impl Active for Input {} + +/// Used by the debugger (type state) +#[derive(Default)] +pub struct Debugger; + +/// Floating input (type state) +#[derive(Default)] +pub struct Floating; + +/// Pulled down input (type state) +#[derive(Default)] +pub struct PullDown; + +/// Pulled up input (type state) +#[derive(Default)] +pub struct PullUp; + +/// Output mode (type state) +#[derive(Default)] +pub struct Output(PhantomData); + +impl Active for Output {} + +/// Open drain input or output (type state) +#[derive(Default)] +pub struct OpenDrain; + +/// Push pull output (type state) +#[derive(Default)] +pub struct PushPull; + +/// Analog mode (type state) +#[derive(Default)] +pub struct Analog; + +impl Active for Analog {} + +/// Alternate function mode (type state) +#[derive(Default)] +pub struct Alternate(PhantomData); + +impl Active for Alternate {} + +/// Alternate function 0 +#[derive(Default)] +pub struct AF0; +/// Alternate function 1 +#[derive(Default)] +pub struct AF1; +/// Alternate function 2 +#[derive(Default)] +pub struct AF2; +/// Alternate function 3 +#[derive(Default)] +pub struct AF3; +/// Alternate function 4 +#[derive(Default)] +pub struct AF4; +/// Alternate function 5 +#[derive(Default)] +pub struct AF5; +/// Alternate function 6 +#[derive(Default)] +pub struct AF6; +/// Alternate function 7 +#[derive(Default)] +pub struct AF7; +/// Alternate function 8 +#[derive(Default)] +pub struct AF8; +/// Alternate function 9 +#[derive(Default)] +pub struct AF9; +/// Alternate function 10 +#[derive(Default)] +pub struct AF10; +/// Alternate function 11 +#[derive(Default)] +pub struct AF11; +/// Alternate function 12 +#[derive(Default)] +pub struct AF12; +/// Alternate function 13 +#[derive(Default)] +pub struct AF13; +/// Alternate function 14 +#[derive(Default)] +pub struct AF14; +/// Alternate function 15 +#[derive(Default)] +pub struct AF15; + +/// Digital output pin state +pub use embedded_hal_02::digital::v2::PinState; // Using SCREAMING_SNAKE_CASE to be consistent with other HALs // see 59b2740 and #125 for motivation @@ -54,11 +217,22 @@ pub enum Edge { mod sealed { /// Marker trait that show if `ExtiPin` can be implemented pub trait Interruptable {} + + pub trait PinMode: Default { + const CNF: super::Cnf; + const MODE: super::Mode; + const PULL: Option = None; + const AF: Option = None; + } } +use crate::pac::gpioa::{afrl::AFSEL0_A as Af, moder::MODE0_A as Mode, otyper::OT0_A as Cnf}; + use sealed::Interruptable; +pub(crate) use sealed::PinMode; impl Interruptable for Input {} +impl Interruptable for Dynamic {} /// External Interrupt Pin pub trait ExtiPin { @@ -165,670 +339,872 @@ where } } -/// Alternate function 0 -pub struct AF0; -/// Alternate function 1 -pub struct AF1; -/// Alternate function 2 -pub struct AF2; -/// Alternate function 3 -pub struct AF3; -/// Alternate function 4 -pub struct AF4; -/// Alternate function 5 -pub struct AF5; -/// Alternate function 6 -pub struct AF6; -/// Alternate function 7 -pub struct AF7; -/// Alternate function 8 -pub struct AF8; -/// Alternate function 9 -pub struct AF9; -/// Alternate function 10 -pub struct AF10; -/// Alternate function 11 -pub struct AF11; -/// Alternate function 12 -pub struct AF12; -/// Alternate function 13 -pub struct AF13; -/// Alternate function 14 -pub struct AF14; -/// Alternate function 15 -pub struct AF15; +/// Tracks the current pin state for dynamic pins +pub enum Dynamic { + InputFloating, + InputPullUp, + InputPullDown, + OutputPushPull, + OutputOpenDrain, +} -/// Alternate function mode (type state) -#[derive(Default)] -pub struct Alternate { - _mode: PhantomData, +impl Default for Dynamic { + fn default() -> Self { + Dynamic::InputFloating + } } -/// Input mode (type state) -#[derive(Default)] -pub struct Input { - _mode: PhantomData, +impl Active for Dynamic {} + +/// `Dynamic` pin error +#[derive(Debug, PartialEq, Eq)] +pub enum PinModeError { + IncorrectMode, } -/// Floating input (type state) -#[derive(Default)] -pub struct Floating; +impl Dynamic { + fn is_input(&self) -> bool { + use Dynamic::*; + match self { + InputFloating | InputPullUp | InputPullDown | OutputOpenDrain => true, + OutputPushPull => false, + } + } -/// Pulled down input (type state) -#[derive(Default)] -pub struct PullDown; + fn is_output(&self) -> bool { + use Dynamic::*; + match self { + InputFloating | InputPullUp | InputPullDown => false, + OutputPushPull | OutputOpenDrain => true, + } + } +} -/// Pulled up input (type state) -#[derive(Default)] -pub struct PullUp; +macro_rules! gpio { + ($GPIOX:ident, $gpiox:ident, $PXx:ident, $port_id:expr, [ + $($PXi:ident: ($pxi:ident, $pin_number:expr $(, $MODE:ty)?),)+ + ]) => { + /// GPIO + pub mod $gpiox { + + use crate::{ + rcc::{Enable, Reset}, + pac::RCC, + pac::$GPIOX + }; + + use super::{ + Active, PartiallyErasedPin, ErasedPin, Floating, GpioExt, Input, + Pin, + }; + #[allow(unused)] + use super::Debugger; + + /// GPIO parts + pub struct Parts { + $( + /// Pin + pub $pxi: $PXi $(<$MODE>)?, + )+ + } -/// Open drain input or output (type state) -#[derive(Default)] -pub struct OpenDrain; + $( + pub type $PXi> = Pin<$port_id, $pin_number, MODE>; + )+ -/// Analog mode (type state) -#[derive(Default)] -pub struct Analog; + impl GpioExt for $GPIOX { + type Parts = Parts; -/// Output mode (type state) -#[derive(Default)] -pub struct Output { - _mode: PhantomData, -} + fn split(self) -> Parts { + let rcc = unsafe { &(*RCC::ptr()) }; + $GPIOX::enable(rcc); + $GPIOX::reset(rcc); -/// Used by the debugger (type state) -#[derive(Default)] -pub struct Debugger; + Parts { + $( + $pxi: $PXi::new(), + )+ + } + } -/// Push pull output (type state) -#[derive(Default)] -pub struct PushPull; + unsafe fn split_without_reset(self) -> Parts { + let rcc = unsafe { &(*RCC::ptr()) }; + $GPIOX::enable(rcc); -/// Fully erased pin -pub struct Pin { - i: u8, - p: u8, - port: *const dyn GpioRegExt, - _mode: PhantomData, + Parts { + $( + $pxi: $PXi::new(), + )+ + } + } + } + + impl PartiallyErasedPin<$port_id, MODE> { + pub fn erase(self) -> ErasedPin { + ErasedPin::$PXx(self) + } + } + + impl Pin<$port_id, N, MODE> + where + MODE: Active, + { + /// Erases the pin number and port 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 erase(self) -> ErasedPin { + self.erase_number().erase() + } + } + } + pub use $gpiox::{ $($PXi,)+ }; + } +} + +/// Generic pin type +/// +/// - `P` is port name: `A` for GPIOA, `B` for GPIOB, etc. +/// - `N` is pin number: from `0` to `15`. +/// - `MODE` is one of the pin modes (see [Modes](crate::gpio#modes) section). +pub struct Pin> { + mode: MODE, } -// NOTE(unsafe) The only write access is to BSRR, which is thread safe -unsafe impl Sync for Pin {} -// NOTE(unsafe) this only enables read access to the same pin from multiple -// threads -unsafe impl Send for Pin {} +impl Pin { + fn new() -> Self { + Self { + mode: Default::default(), + } + } +} -impl PinExt for Pin { +impl PinExt for Pin { type Mode = MODE; fn pin_id(&self) -> u8 { - self.i + N } fn port_id(&self) -> u8 { - self.p + P as u8 } } -macro_rules! gpio_trait { - ($gpiox:ident) => { - impl GpioRegExt for crate::pac::$gpiox::RegisterBlock { - fn is_low(&self, pos: u8) -> bool { - // NOTE(unsafe) atomic read with no side effects - self.idr.read().bits() & (1 << pos) == 0 - } +impl Pin { + /// Put the pin in an active state. The caller + /// must enforce that the pin is really in this + /// state in the hardware. + #[allow(dead_code)] + pub(crate) unsafe fn activate(self) -> Pin> { + Pin::new() + } +} - fn is_set_low(&self, pos: u8) -> bool { - // NOTE(unsafe) atomic read with no side effects - self.odr.read().bits() & (1 << pos) == 0 - } +// Internal helper functions + +// NOTE: The functions in this impl block are "safe", but they +// are callable when the pin is in modes where they don't make +// sense. +impl Pin { + /** + Set the output of the pin regardless of its mode. + Primarily used to set the output value of the 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 { + PinState::High => self._set_high(), + PinState::Low => self._set_low(), + } + } - fn set_high(&self, pos: u8) { - // NOTE(unsafe) atomic write to a stateless register - unsafe { self.bsrr.write(|w| w.bits(1 << pos)) } - } + #[inline(always)] + fn _set_high(&mut self) { + // NOTE(unsafe) atomic write to a stateless register + let gpio = unsafe { &(*gpiox::

()) }; + unsafe { gpio.bsrr.write(|w| w.bits(1 << N)) } + } - fn set_low(&self, pos: u8) { - // NOTE(unsafe) atomic write to a stateless register - unsafe { self.bsrr.write(|w| w.bits(1 << (pos + 16))) } - } + #[inline(always)] + fn _set_low(&mut self) { + // NOTE(unsafe) atomic write to a stateless register + let gpio = unsafe { &(*gpiox::

()) }; + unsafe { gpio.bsrr.write(|w| w.bits(1 << (N + 16))) } + } + + #[inline(always)] + fn _is_set_low(&self) -> bool { + // NOTE(unsafe) atomic read with no side effects + let gpio = unsafe { &(*gpiox::

()) }; + gpio.odr.read().bits() & (1 << N) == 0 + } + + #[inline(always)] + fn _is_low(&self) -> bool { + // NOTE(unsafe) atomic read with no side effects + let gpio = unsafe { &(*gpiox::

()) }; + gpio.idr.read().bits() & (1 << N) != 0 + } +} + +impl Pin +where + MODE: Active, +{ + /// Erases the pin number from the type + #[inline] + pub fn erase_number(self) -> PartiallyErasedPin { + PartiallyErasedPin::new(N) + } +} + +impl Pin> { + #[inline] + pub fn set_high(&mut self) { + self._set_high() + } + + #[inline] + pub fn set_low(&mut self) { + self._set_low() + } + + #[inline(always)] + pub fn get_state(&self) -> PinState { + if self._is_set_low() { + PinState::Low + } else { + PinState::High + } + } + + #[inline(always)] + pub fn set_state(&mut self, state: PinState) { + self._set_state(state) + } + + #[inline] + pub fn is_set_high(&self) -> bool { + !self._is_set_low() + } + + #[inline] + pub fn is_set_low(&self) -> bool { + self._is_set_low() + } + + #[inline] + pub fn toggle(&mut self) { + if self._is_set_low() { + self._set_high() + } else { + self._set_low() + } + } +} + +impl Pin> { + #[inline] + pub fn is_high(&self) -> bool { + !self._is_low() + } + + #[inline] + pub fn is_low(&self) -> bool { + self._is_low() + } +} + +impl Pin> { + #[inline] + pub fn is_high(&self) -> bool { + !self._is_low() + } + + #[inline] + pub fn is_low(&self) -> bool { + self._is_low() + } +} + +impl Pin +where + MODE: Active, +{ + /// Configures the pin to operate as a floating input pin + #[inline] + pub fn into_floating_input(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate as a pulled down input pin + #[inline] + pub fn into_pull_down_input(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate as a pulled up input pin + #[inline] + pub fn into_pull_up_input(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate as an open-drain output pin. + /// Initial state will be low. + #[inline] + pub fn into_open_drain_output(self) -> Pin> { + self.into_open_drain_output_with_state(PinState::Low) + } + + /// Configures the pin to operate as an open-drain output pin. + /// `initial_state` specifies whether the pin should be initially high or low. + #[inline] + pub fn into_open_drain_output_with_state( + mut self, + initial_state: PinState, + ) -> Pin> { + self._set_state(initial_state); + self.into_mode() + } + + /// Configures the pin to operate as an push-pull output pin. + /// Initial state will be low. + #[inline] + pub fn into_push_pull_output(self) -> Pin> { + self.into_push_pull_output_with_state(PinState::Low) + } + + /// Configures the pin to operate as an push-pull output pin. + /// `initial_state` specifies whether the pin should be initially high or low. + #[inline] + pub fn into_push_pull_output_with_state( + mut self, + initial_state: PinState, + ) -> Pin> { + self._set_state(initial_state); + self.into_mode() + } + + /// Configures the pin to operate as an push-pull output pin. + /// The state will not be changed. + #[inline] + pub fn into_push_pull_output_with_current_state(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate as an analog input pin + #[inline] + pub fn into_analog(self) -> Pin { + self.into_mode() + } + + /// Configures the pin to operate in AF0 mode + #[inline] + pub fn into_alternate_af0(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate in AF1 mode + #[inline] + pub fn into_alternate_af1(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate in AF2 mode + #[inline] + pub fn into_alternate_af2(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate in AF3 mode + #[inline] + pub fn into_alternate_af3(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate in AF4 mode + #[inline] + pub fn into_alternate_af4(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate in AF5 mode + #[inline] + pub fn into_alternate_af5(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate in AF6 mode + #[inline] + pub fn into_alternate_af6(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate in AF7 mode + #[inline] + pub fn into_alternate_af7(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate in AF8 mode + #[inline] + pub fn into_alternate_af8(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate in AF9 mode + #[inline] + pub fn into_alternate_af9(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate in AF10 mode + #[inline] + pub fn into_alternate_af10(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate in AF11 mode + #[inline] + pub fn into_alternate_af11(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate in AF12 mode + #[inline] + pub fn into_alternate_af12(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate in AF13 mode + #[inline] + pub fn into_alternate_af13(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate in AF14 mode + #[inline] + pub fn into_alternate_af14(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin to operate in AF15 mode + #[inline] + pub fn into_alternate_af15(self) -> Pin> { + self.into_mode() + } + + /// Configures the pin as a pin that can change between input + /// and output without changing the type. It starts out + /// as a floating input + #[inline] + pub fn into_dynamic(mut self) -> Pin { + self.mode::>(); + Pin::new() + } +} + +// These macros are defined here instead of at the top level in order +// to be able to refer to macro variables from the outer layers. +macro_rules! impl_temp_output { + ($fn_name:ident, $stateful_fn_name:ident, $mode:ty) => { + /// Temporarily change the mode of the pin. + /// + /// The value of the pin after conversion is undefined. If you + /// want to control it, use `$stateful_fn_name` + #[inline] + pub fn $fn_name(&mut self, mut f: impl FnMut(&mut Pin)) { + self.mode::<$mode>(); + let mut temp = Pin::::new(); + f(&mut temp); + self.mode::<$mode>(); + Self::new(); + } + + /// Temporarily change the mode of the pin. + /// + /// Note that the new state is set slightly before conversion + /// happens. This can cause a short output glitch if switching + /// between output modes + #[inline] + pub fn $stateful_fn_name( + &mut self, + state: PinState, + mut f: impl FnMut(&mut Pin), + ) { + self._set_state(state); + self.mode::<$mode>(); + let mut temp = Pin::::new(); + f(&mut temp); + self.mode::<$mode>(); + Self::new(); + } + }; +} +macro_rules! impl_temp_input { + ($fn_name:ident, $mode:ty) => { + /// Temporarily change the mode of the pin. + #[inline] + pub fn $fn_name(&mut self, mut f: impl FnMut(&mut Pin)) { + self.mode::<$mode>(); + let mut temp = Pin::::new(); + f(&mut temp); + self.mode::<$mode>(); + Self::new(); } }; } -gpio_trait!(gpioa); +impl Pin +where + MODE: Active + PinMode, +{ + impl_temp_output!( + as_push_pull_output, + as_push_pull_output_with_state, + Output + ); + impl_temp_output!( + as_open_drain_output, + as_open_drain_output_with_state, + Output + ); + impl_temp_input!(as_floating_input, Input); + impl_temp_input!(as_pull_up_input, Input); + impl_temp_input!(as_pull_down_input, Input); +} -#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] -gpio_trait!(gpiof); -#[cfg(feature = "py32f002b")] -gpio_trait!(gpioc); +// Dynamic pin -macro_rules! gpio { - ([$($GPIOX:ident, $gpiox:ident, $PCH:literal, $gate:meta => [ - $($PXi:ident: ($pxi:ident, $i:expr, $MODE:ty),)+ - ]),+]) => { - $( - /// GPIO - #[cfg($gate)] - pub mod $gpiox { - use core::marker::PhantomData; - - use crate::{ - rcc::{Enable, Reset}, - pac::RCC, - pac::$GPIOX - }; - - use super::{ - Alternate, Analog, Floating, GpioExt, Input, OpenDrain, Output, - PullDown, PullUp, PushPull, AF0, AF1, AF2, AF3, AF4, AF5, AF6, AF7, - AF8, AF9, AF10, AF11, AF12, AF13, AF14, AF15, Pin, GpioRegExt, - }; - - /// GPIO parts - pub struct Parts { - $( - /// Pin - pub $pxi: $PXi<$MODE>, - )+ - } +impl Pin { + #[inline] + pub fn make_pull_up_input(&mut self) { + // NOTE(unsafe), we have a mutable reference to the current pin + self.mode::>(); + self.mode = Dynamic::InputPullUp; + } - impl GpioExt for $GPIOX { - type Parts = Parts; + #[inline] + pub fn make_pull_down_input(&mut self) { + // NOTE(unsafe), we have a mutable reference to the current pin + self.mode::>(); + self.mode = Dynamic::InputPullDown; + } - fn split(self) -> Parts { - let rcc = unsafe { &(*RCC::ptr()) }; - $GPIOX::enable(rcc); - $GPIOX::reset(rcc); + #[inline] + pub fn make_floating_input(&mut self) { + // NOTE(unsafe), we have a mutable reference to the current pin + self.mode::>(); + self.mode = Dynamic::InputFloating; + } - Parts { - $( - $pxi: $PXi { _mode: PhantomData }, - )+ - } - } + #[inline] + pub fn make_push_pull_output(&mut self) { + // NOTE(unsafe), we have a mutable reference to the current pin + self.mode::>(); + self.mode = Dynamic::OutputPushPull; + } - unsafe fn split_without_reset(self) -> Parts { - let rcc = unsafe { &(*RCC::ptr()) }; - $GPIOX::enable(rcc); + #[inline] + pub fn make_open_drain_output(&mut self) { + // NOTE(unsafe), we have a mutable reference to the current pin + self.mode::>(); + self.mode = Dynamic::OutputOpenDrain; + } +} - Parts { - $( - $pxi: $PXi { _mode: PhantomData }, - )+ - } - } - } +impl PinMode for Analog { + const MODE: Mode = Mode::Analog; + const CNF: Cnf = Cnf::PushPull; +} + +impl PinMode for Input { + const MODE: Mode = Mode::Input; + const CNF: Cnf = Cnf::PushPull; +} + +impl PinMode for Input { + const MODE: Mode = Mode::Input; + const CNF: Cnf = Cnf::PushPull; + const PULL: Option = Some(false); +} + +impl PinMode for Input { + const MODE: Mode = Mode::Input; + const CNF: Cnf = Cnf::PushPull; + const PULL: Option = Some(true); +} + +impl PinMode for Output { + const MODE: Mode = Mode::Output; + const CNF: Cnf = Cnf::PushPull; +} + +impl PinMode for Output { + const MODE: Mode = Mode::Output; + const CNF: Cnf = Cnf::OpenDrain; +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af0); +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af1); +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af2); +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af3); +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af4); +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af5); +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af6); +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af7); +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af8); +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af9); +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af10); +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af11); +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af12); +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af13); +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af14); +} + +impl PinMode for Alternate { + const MODE: Mode = Mode::Alternate; + const CNF: Cnf = Cnf::PushPull; + const AF: Option = Some(Af::Af15); +} + +impl Pin { + fn mode(&mut self) { + let gpio = unsafe { &(*gpiox::

()) }; + + let offset2 = 2 * N; + // set pull up/down if necessary + if let Some(pull) = MODE::PULL { + let pupdv = if pull { 0b01 } else { 0b11 }; + unsafe { + gpio.pupdr + .modify(|r, w| w.bits((r.bits() & !(0b11 << offset2)) | (pupdv << offset2))) + }; + } - fn _set_alternate_mode (index:usize, mode: u32) - { - let offset = 2 * index; - let offset2 = 4 * index; - unsafe { - let reg = &(*$GPIOX::ptr()); - if offset2 < 32 { - reg.afrl.modify(|r, w| { - w.bits((r.bits() & !(0b1111 << offset2)) | (mode << offset2)) - }); - } else { - #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] { - let offset2 = offset2 - 32; - reg.afrh.modify(|r, w| { - w.bits((r.bits() & !(0b1111 << offset2)) | (mode << offset2)) - }); - } - - #[cfg(not(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a")))] { - // py32f002b does only have a maximum of 8 pins per port so it does not have AFRH - unreachable!(); - } - } - reg.moder.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b10 << offset)) + // set the mode + let mv: u8 = MODE::MODE.into(); + unsafe { + gpio.moder + .modify(|r, w| w.bits((r.bits() & !(0b11 << offset2)) | ((mv as u32) << offset2))) + }; + // if an output, set output type + if MODE::MODE == Mode::Output { + let otyperv = if MODE::CNF == Cnf::OpenDrain { + 0b1 << N + } else { + !(0b1 << N) + }; + unsafe { gpio.otyper.modify(|r, w| w.bits(r.bits() | otyperv)) }; + } + // if an alternate function pin, set that + if let Some(af) = MODE::AF { + let afv: u8 = af.into(); + unsafe { + if N < 8 { + let offset4 = N * 4; + gpio.afrl.modify(|r, w| { + w.bits((r.bits() & !(0b1111 << offset4)) | ((afv as u32) << offset4)) + }); + } else { + #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] + { + let offset4 = (N - 8) * 4; + gpio.afrh.modify(|r, w| { + w.bits((r.bits() & !(0b1111 << offset4)) | ((afv as u32) << offset4)) }); } + #[cfg(feature = "py32f002b")] + { + // py32f002b does only have a maximum of 8 pins per port so it does not have AFRH + unreachable!(); + } } + } + } + } - $( - /// Pin - pub struct $PXi { - _mode: PhantomData, - } + #[inline] + pub(crate) fn into_mode(mut self) -> Pin { + self.mode::(); + Pin::new() + } +} - impl $PXi { - /// Configures the pin to operate in AF0 mode - pub fn into_alternate_af0( - self, - ) -> $PXi> { - _set_alternate_mode($i, 0); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate in AF1 mode - pub fn into_alternate_af1( - self, - ) -> $PXi> { - _set_alternate_mode($i, 1); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate in AF2 mode - pub fn into_alternate_af2( - self, - ) -> $PXi> { - _set_alternate_mode($i, 2); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate in AF3 mode - pub fn into_alternate_af3( - self, - ) -> $PXi> { - _set_alternate_mode($i, 3); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate in AF4 mode - pub fn into_alternate_af4( - self, - ) -> $PXi> { - _set_alternate_mode($i, 4); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate in AF5 mode - pub fn into_alternate_af5( - self, - ) -> $PXi> { - _set_alternate_mode($i, 5); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate in AF6 mode - pub fn into_alternate_af6( - self, - ) -> $PXi> { - _set_alternate_mode($i, 6); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate in AF7 mode - pub fn into_alternate_af7( - self, - ) -> $PXi> { - _set_alternate_mode($i, 7); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate in AF8 mode - pub fn into_alternate_af8( - self, - ) -> $PXi> { - _set_alternate_mode($i, 8); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate in AF9 mode - pub fn into_alternate_af9( - self, - ) -> $PXi> { - _set_alternate_mode($i, 9); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate in AF10 mode - pub fn into_alternate_af10( - self, - ) -> $PXi> { - _set_alternate_mode($i, 10); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate in AF11 mode - pub fn into_alternate_af11( - self, - ) -> $PXi> { - _set_alternate_mode($i, 11); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate in AF12 mode - pub fn into_alternate_af12( - self, - ) -> $PXi> { - _set_alternate_mode($i, 12); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate in AF13 mode - pub fn into_alternate_af13( - self, - ) -> $PXi> { - _set_alternate_mode($i, 13); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate in AF14 mode - pub fn into_alternate_af14( - self, - ) -> $PXi> { - _set_alternate_mode($i, 14); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate in AF15 mode - pub fn into_alternate_af15( - self, - ) -> $PXi> { - _set_alternate_mode($i, 15); - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate as a floating input pin - pub fn into_floating_input( - self, - ) -> $PXi> { - let offset = 2 * $i; - unsafe { - let reg = &(*$GPIOX::ptr()); - reg.pupdr.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b00 << offset)) - }); - reg.moder.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b00 << offset)) - }); - } - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate as a pulled down input pin - pub fn into_pull_down_input( - self, - ) -> $PXi> { - let offset = 2 * $i; - unsafe { - let reg = &(*$GPIOX::ptr()); - reg.pupdr.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b10 << offset)) - }); - reg.moder.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b00 << offset)) - }); - } - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate as a pulled up input pin - pub fn into_pull_up_input( - self, - ) -> $PXi> { - let offset = 2 * $i; - unsafe { - let reg = &(*$GPIOX::ptr()); - reg.pupdr.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b01 << offset)) - }); - reg.moder.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b00 << offset)) - }); - } - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate as an analog pin - pub fn into_analog( - self, - ) -> $PXi { - let offset = 2 * $i; - unsafe { - let reg = &(*$GPIOX::ptr()); - reg.pupdr.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b00 << offset)) - }); - reg.moder.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b11 << offset)) - }); - } - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate as an open drain output pin - pub fn into_open_drain_output( - self, - ) -> $PXi> { - let offset = 2 * $i; - unsafe { - let reg = &(*$GPIOX::ptr()); - reg.pupdr.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b00 << offset)) - }); - reg.otyper.modify(|r, w| { - w.bits(r.bits() | (0b1 << $i)) - }); - reg.moder.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b01 << offset)) - }); - } - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate as an push pull output pin - pub fn into_push_pull_output( - self, - ) -> $PXi> { - let offset = 2 * $i; - unsafe { - let reg = &(*$GPIOX::ptr()); - reg.pupdr.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b00 << offset)) - }); - reg.otyper.modify(|r, w| { - w.bits(r.bits() & !(0b1 << $i)) - }); - reg.moder.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b01 << offset)) - }); - } - $PXi { _mode: PhantomData } - } - - /// Configures the pin to operate as an push pull output pin with quick fall - /// and rise times - pub fn into_push_pull_output_hs( - self, - ) -> $PXi> { - let offset = 2 * $i; - unsafe { - let reg = &(*$GPIOX::ptr()); - reg.pupdr.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b00 << offset)) - }); - reg.otyper.modify(|r, w| { - w.bits(r.bits() & !(0b1 << $i)) - }); - reg.ospeedr.modify(|r, w| { - w.bits(r.bits() & !(0b1 << $i)) - }); - reg.moder.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (0b01 << offset)) - }); - } - $PXi { _mode: PhantomData } - } - } +impl Analog { + pub fn new(pin: Pin) -> Pin + where + Self: PinMode, + { + pin.into_mode() + } +} - impl $PXi> { - /// Enables / disables the internal pull up - pub fn internal_pull_up(&mut self, on: bool) { - let offset = 2 * $i; - let value = if on { 0b01 } else { 0b00 }; - unsafe { - let reg = &(*$GPIOX::ptr()); - reg.pupdr.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (value << offset)) - }); - } - } - } +impl Input { + pub fn new( + pin: Pin, + _pull: PULL, + ) -> Pin + where + Self: PinMode, + { + pin.into_mode() + } +} - impl $PXi> { - /// Enables / disables the internal pull up - pub fn internal_pull_up(self, on: bool) -> Self { - let offset = 2 * $i; - let value = if on { 0b01 } else { 0b00 }; - unsafe { - let reg = &(*$GPIOX::ptr()); - reg.pupdr.modify(|r, w| { - w.bits((r.bits() & !(0b11 << offset)) | (value << offset)) - }); - } - self - } - } +impl Output { + pub fn new( + mut pin: Pin, + state: PinState, + ) -> Pin + where + Self: PinMode, + { + pin._set_state(state); + pin.into_mode() + } +} - impl $PXi> { - /// Turns pin alternate configuration pin into open drain - pub fn set_open_drain(self) -> Self { - let offset = $i; - unsafe { - let reg = &(*$GPIOX::ptr()); - reg.otyper.modify(|r, w| { - w.bits(r.bits() | (1 << offset)) - }); - } - self - } - } +impl Alternate { + pub fn new(pin: Pin) -> Pin + where + Self: PinMode, + { + pin.into_mode() + } +} - impl $PXi> { - pub fn is_set_high(&mut self) -> bool { - !self.is_set_low() - } - - pub fn is_set_low(&mut self) -> bool { - unsafe { (*$GPIOX::ptr()).is_set_low($i) } - } - - pub fn set_high(&mut self) { - unsafe { (*$GPIOX::ptr()).set_high($i) }; - } - - #[allow(dead_code)] - pub fn set_low(&mut self) { - unsafe { (*$GPIOX::ptr()).set_low($i) }; - } - - #[allow(dead_code)] - pub fn is_high(&mut self) -> bool { - !self.is_low() - } - - #[allow(dead_code)] - pub fn is_low(&mut self) -> bool { - unsafe { (*$GPIOX::ptr()).is_low($i) } - } - - pub fn toggle(&mut self) { - if self.is_low() { - self.set_high(); - } else { - self.set_low(); - } - } - - /// 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) -> Pin> { - Pin { - i: $i, - p: $PCH, - port: $GPIOX::ptr() as *const dyn GpioRegExt, - _mode: self._mode, - } - } - } +gpio!(GPIOA, gpioa, PAx, 'A', [ + PA0: (pa0, 0), + PA1: (pa1, 1), + PA2: (pa2, 2), + PA3: (pa3, 3), + PA4: (pa4, 4), + PA5: (pa5, 5), + PA6: (pa6, 6), + PA7: (pa7, 7), + PA8: (pa8, 8), + PA9: (pa9, 9), + PA10: (pa10, 10), + PA11: (pa11, 11), + PA12: (pa12, 12), + PA13: (pa13, 13, Debugger), + PA14: (pa14, 14, Debugger), + PA15: (pa15, 15), +]); - impl $PXi> { - pub fn is_high(&mut self) -> bool { - !self.is_low() - } - - pub fn is_low(&mut self) -> bool { - unsafe { (*$GPIOX::ptr()).is_low($i) } - } - - /// 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) -> Pin> { - Pin { - i: $i, - p: $PCH, - port: $GPIOX::ptr() as *const dyn GpioRegExt, - _mode: self._mode, - } - } - } +gpio!(GPIOB, gpiob, PBx, 'B', [ + PB0: (pb0, 0), + PB1: (pb1, 1), + PB2: (pb2, 2), + PB3: (pb3, 3), + PB4: (pb4, 4), + PB5: (pb5, 5), + PB6: (pb6, 6), + PB7: (pb7, 7), + PB8: (pb8, 8), +]); - )+ - } - )+ - } -} - -gpio!([ - // BUGBUG: py32f002b only has 8 pins? - GPIOA, gpioa, b'A', any( - feature = "device-selected" - ) => [ - PA0: (pa0, 0, Input), - PA1: (pa1, 1, Input), - PA2: (pa2, 2, Input), - PA3: (pa3, 3, Input), - PA4: (pa4, 4, Input), - PA5: (pa5, 5, Input), - PA6: (pa6, 6, Input), - PA7: (pa7, 7, Input), - PA8: (pa8, 8, Input), - PA9: (pa9, 9, Input), - PA10: (pa10, 10, Input), - PA11: (pa11, 11, Input), - PA12: (pa12, 12, Input), - PA13: (pa13, 13, Input), - PA14: (pa14, 14, Input), - PA15: (pa15, 15, Input), - ], - GPIOB, gpiob, b'B', any( - feature = "device-selected" - ) => [ - PB0: (pb0, 0, Input), - PB1: (pb1, 1, Input), - PB2: (pb2, 2, Input), - PB3: (pb3, 3, Input), - PB4: (pb4, 4, Input), - PB5: (pb5, 5, Input), - PB6: (pb6, 6, Input), - PB7: (pb7, 7, Input), - PB8: (pb8, 8, Input), - ], - GPIOC, gpioc, b'C', any( - feature = "py32f002b" - ) => [ - PC0: (pf0, 0, Input), - PC1: (pf1, 1, Input), - ], - GPIOF, gpiof, b'F', any( - feature = "py32f030", - feature = "py32f003", - feature = "py32f002a" - ) => [ - PF0: (pf0, 0, Input), - PF1: (pf1, 1, Input), - PF2: (pf2, 2, Input), - PF3: (pf3, 3, Input), - PF4: (pf4, 4, Input), - ] +#[cfg(feature = "py32f002b")] +gpio!(GPIOC, gpioc, PCx, 'C', [ + PC0: (pc0, 0), + PC1: (pc1, 1), ]); + +#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] +gpio!(GPIOF, gpiof, PFx, 'F', [ + PF0: (pf0, 0), + PF1: (pf1, 1), + PF2: (pf2, 2), + PF3: (pf3, 3), + PF4: (pf4, 4), +]); + +const fn gpiox() -> *const crate::pac::gpioa::RegisterBlock { + match P { + 'A' => crate::pac::GPIOA::ptr(), + 'B' => crate::pac::GPIOB::ptr() as _, + #[cfg(feature = "py32f002b")] + 'C' => crate::pac::GPIOC::ptr() as _, + #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] + 'F' => crate::pac::GPIOF::ptr() as _, + _ => unreachable!(), + } +} diff --git a/src/gpio/erased.rs b/src/gpio/erased.rs new file mode 100644 index 0000000..1480024 --- /dev/null +++ b/src/gpio/erased.rs @@ -0,0 +1,130 @@ +use super::*; + +pub type AnyPin = ErasedPin; + +macro_rules! impl_pxx { + ($(($port_id:literal :: $pin:ident)),*) => { + /// Erased pin + /// + /// `MODE` is one of the pin modes (see [Modes](crate::gpio#modes) section). + pub enum ErasedPin { + $( + $pin(PartiallyErasedPin<$port_id, MODE>) + ),* + } + + impl PinExt for ErasedPin { + type Mode = MODE; + + #[inline(always)] + fn pin_id(&self) -> u8 { + match self { + $(Self::$pin(pin) => pin.pin_id()),* + } + } + + #[inline(always)] + fn port_id(&self) -> u8 { + match self { + $(Self::$pin(pin) => pin.port_id()),* + } + } + } + + impl ErasedPin> { + pub fn set_high(&mut self) { + match self { + $(Self::$pin(pin) => pin.set_high()),* + } + } + + pub fn set_low(&mut self) { + match self { + $(Self::$pin(pin) => pin.set_low()),* + } + } + + pub fn is_set_high(&self) -> bool { + match self { + $(Self::$pin(pin) => pin.is_set_high()),* + } + } + + pub fn is_set_low(&self) -> bool { + match self { + $(Self::$pin(pin) => pin.is_set_low()),* + } + } + } + + impl ErasedPin> { + pub fn is_high(&self) -> bool { + match self { + $(Self::$pin(pin) => pin.is_high()),* + } + } + + pub fn is_low(&self) -> bool { + match self { + $(Self::$pin(pin) => pin.is_low()),* + } + } + } + + impl ErasedPin> { + pub fn is_high(&self) -> bool { + match self { + $(Self::$pin(pin) => pin.is_high()),* + } + } + + pub fn is_low(&self) -> bool { + match self { + $(Self::$pin(pin) => pin.is_low()),* + } + } + } + } +} + +impl ErasedPin> { + #[inline(always)] + pub fn get_state(&self) -> PinState { + if self.is_set_low() { + PinState::Low + } else { + PinState::High + } + } + + #[inline(always)] + pub fn set_state(&mut self, state: PinState) { + match state { + PinState::Low => self.set_low(), + PinState::High => self.set_high(), + } + } + + #[inline(always)] + pub fn toggle(&mut self) { + if self.is_set_low() { + self.set_high() + } else { + self.set_low() + } + } +} + +#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] +impl_pxx! { + ('A'::PAx), + ('B'::PBx), + ('F'::PFx) +} + +#[cfg(feature = "py32f002b")] +impl_pxx! { + ('A'::PAx), + ('B'::PBx), + ('C'::PCx) +} diff --git a/src/gpio/hal_02.rs b/src/gpio/hal_02.rs index b25ae16..7759be4 100644 --- a/src/gpio/hal_02.rs +++ b/src/gpio/hal_02.rs @@ -4,170 +4,198 @@ use embedded_hal_02::digital::v2::{toggleable, InputPin, OutputPin, StatefulOutp // Pin -impl OutputPin for Pin> { +impl OutputPin for Pin { + type Error = PinModeError; + fn set_high(&mut self) -> Result<(), Self::Error> { + if self.mode.is_output() { + self._set_state(PinState::High); + Ok(()) + } else { + Err(PinModeError::IncorrectMode) + } + } + fn set_low(&mut self) -> Result<(), Self::Error> { + if self.mode.is_output() { + self._set_state(PinState::Low); + Ok(()) + } else { + Err(PinModeError::IncorrectMode) + } + } +} + +impl InputPin for Pin { + type Error = PinModeError; + fn is_high(&self) -> Result { + self.is_low().map(|b| !b) + } + fn is_low(&self) -> Result { + if self.mode.is_input() { + Ok(self._is_low()) + } else { + Err(PinModeError::IncorrectMode) + } + } +} + +impl OutputPin for Pin> { type Error = Infallible; #[inline] fn set_high(&mut self) -> Result<(), Self::Error> { - unsafe { (*self.port).set_high(self.i) }; + self.set_high(); Ok(()) } #[inline] fn set_low(&mut self) -> Result<(), Self::Error> { - unsafe { (*self.port).set_low(self.i) }; + self.set_low(); Ok(()) } } -impl StatefulOutputPin for Pin> { +impl StatefulOutputPin for Pin> { #[inline] fn is_set_high(&self) -> Result { - self.is_set_low().map(|v| !v) + Ok(self.is_set_high()) } #[inline] fn is_set_low(&self) -> Result { - Ok(unsafe { (*self.port).is_set_low(self.i) }) + Ok(self.is_set_low()) } } -impl InputPin for Pin> { +impl InputPin for Pin> { type Error = Infallible; #[inline] fn is_high(&self) -> Result { - self.is_low().map(|v| !v) + Ok(self.is_high()) } #[inline] fn is_low(&self) -> Result { - Ok(unsafe { (*self.port).is_low(self.i) }) + Ok(self.is_low()) } } -impl InputPin for Pin> { +impl InputPin for Pin> { type Error = Infallible; #[inline] fn is_high(&self) -> Result { - self.is_low().map(|v| !v) + Ok(self.is_high()) } #[inline] fn is_low(&self) -> Result { - Ok(unsafe { (*self.port).is_low(self.i) }) + Ok(self.is_low()) } } -impl toggleable::Default for Pin> {} +impl toggleable::Default for Pin> {} // PartiallyErasedPin -// impl OutputPin for PartiallyErasedPin> { -// type Error = Infallible; - -// #[inline(always)] -// fn set_high(&mut self) -> Result<(), Self::Error> { -// self.set_high(); -// Ok(()) -// } - -// #[inline(always)] -// fn set_low(&mut self) -> Result<(), Self::Error> { -// self.set_low(); -// Ok(()) -// } -// } - -// impl StatefulOutputPin for PartiallyErasedPin> { -// #[inline(always)] -// fn is_set_high(&self) -> Result { -// Ok(self.is_set_high()) -// } - -// #[inline(always)] -// fn is_set_low(&self) -> Result { -// Ok(self.is_set_low()) -// } -// } - -// impl ToggleableOutputPin for PartiallyErasedPin> { -// type Error = Infallible; - -// #[inline(always)] -// fn toggle(&mut self) -> Result<(), Self::Error> { -// self.toggle(); -// Ok(()) -// } -// } - -// impl InputPin for PartiallyErasedPin> { -// type Error = Infallible; - -// #[inline(always)] -// fn is_high(&self) -> Result { -// Ok(self.is_high()) -// } - -// #[inline(always)] -// fn is_low(&self) -> Result { -// Ok(self.is_low()) -// } -// } - -// impl InputPin for PartiallyErasedPin> { -// type Error = Infallible; - -// #[inline(always)] -// fn is_high(&self) -> Result { -// Ok(self.is_high()) -// } - -// #[inline(always)] -// fn is_low(&self) -> Result { -// Ok(self.is_low()) -// } -// } +impl OutputPin for PartiallyErasedPin> { + type Error = Infallible; + + #[inline(always)] + fn set_high(&mut self) -> Result<(), Self::Error> { + self.set_high(); + Ok(()) + } + + #[inline(always)] + fn set_low(&mut self) -> Result<(), Self::Error> { + self.set_low(); + Ok(()) + } +} + +impl StatefulOutputPin for PartiallyErasedPin> { + #[inline(always)] + fn is_set_high(&self) -> Result { + Ok(self.is_set_high()) + } + + #[inline(always)] + fn is_set_low(&self) -> Result { + Ok(self.is_set_low()) + } +} + +impl InputPin for PartiallyErasedPin> { + type Error = Infallible; + + #[inline(always)] + fn is_high(&self) -> Result { + Ok(self.is_high()) + } + + #[inline(always)] + fn is_low(&self) -> Result { + Ok(self.is_low()) + } +} + +impl InputPin for PartiallyErasedPin> { + type Error = Infallible; + + #[inline(always)] + fn is_high(&self) -> Result { + Ok(self.is_high()) + } + + #[inline(always)] + fn is_low(&self) -> Result { + Ok(self.is_low()) + } +} + +impl toggleable::Default for PartiallyErasedPin> {} // ErasedPin -// impl OutputPin for ErasedPin> { -// type Error = Infallible; -// fn set_high(&mut self) -> Result<(), Infallible> { -// self.set_high(); -// Ok(()) -// } - -// fn set_low(&mut self) -> Result<(), Infallible> { -// self.set_low(); -// Ok(()) -// } -// } - -// impl StatefulOutputPin for ErasedPin> { -// fn is_set_high(&self) -> Result { -// Ok(self.is_set_high()) -// } - -// fn is_set_low(&self) -> Result { -// Ok(self.is_set_low()) -// } -// } - -// impl InputPin for ErasedPin> { -// type Error = Infallible; -// fn is_high(&self) -> Result { -// Ok(self.is_high()) -// } - -// fn is_low(&self) -> Result { -// Ok(self.is_low()) -// } -// } - -// impl InputPin for ErasedPin> { -// type Error = Infallible; -// fn is_high(&self) -> Result { -// Ok(self.is_high()) -// } - -// fn is_low(&self) -> Result { -// Ok(self.is_low()) -// } -// } +impl OutputPin for ErasedPin> { + type Error = Infallible; + fn set_high(&mut self) -> Result<(), Infallible> { + self.set_high(); + Ok(()) + } + + fn set_low(&mut self) -> Result<(), Infallible> { + self.set_low(); + Ok(()) + } +} + +impl StatefulOutputPin for ErasedPin> { + fn is_set_high(&self) -> Result { + Ok(self.is_set_high()) + } + + fn is_set_low(&self) -> Result { + Ok(self.is_set_low()) + } +} + +impl InputPin for ErasedPin> { + type Error = Infallible; + fn is_high(&self) -> Result { + Ok(self.is_high()) + } + + fn is_low(&self) -> Result { + Ok(self.is_low()) + } +} + +impl InputPin for ErasedPin> { + type Error = Infallible; + fn is_high(&self) -> Result { + Ok(self.is_high()) + } + + fn is_low(&self) -> Result { + Ok(self.is_low()) + } +} + +impl toggleable::Default for ErasedPin> {} diff --git a/src/gpio/hal_1.rs b/src/gpio/hal_1.rs index 25813dc..97dee1b 100644 --- a/src/gpio/hal_1.rs +++ b/src/gpio/hal_1.rs @@ -1,166 +1,218 @@ -use super::{Input, OpenDrain, Output, Pin}; +use super::{Dynamic, ErasedPin, Input, OpenDrain, Output, PartiallyErasedPin, Pin, PinModeError}; use core::convert::Infallible; +pub use embedded_hal::digital::PinState; use embedded_hal::digital::{ErrorType, InputPin, OutputPin, StatefulOutputPin}; +fn into_state(state: PinState) -> super::PinState { + match state { + PinState::Low => super::PinState::Low, + PinState::High => super::PinState::High, + } +} + // Implementations for `Pin` -impl ErrorType for Pin> { +impl ErrorType for Pin> { type Error = Infallible; } -impl ErrorType for Pin> { +impl ErrorType for Pin> { type Error = Infallible; } -impl StatefulOutputPin for Pin> { +impl embedded_hal::digital::Error for PinModeError { + fn kind(&self) -> embedded_hal::digital::ErrorKind { + match self { + PinModeError::IncorrectMode => embedded_hal::digital::ErrorKind::Other, + } + } +} + +impl ErrorType for Pin { + type Error = PinModeError; +} + +impl OutputPin for Pin { + fn set_high(&mut self) -> Result<(), Self::Error> { + if self.mode.is_output() { + self._set_state(into_state(PinState::High)); + Ok(()) + } else { + Err(PinModeError::IncorrectMode) + } + } + fn set_low(&mut self) -> Result<(), Self::Error> { + if self.mode.is_output() { + self._set_state(into_state(PinState::Low)); + Ok(()) + } else { + Err(PinModeError::IncorrectMode) + } + } +} + +impl InputPin for Pin { + fn is_high(&mut self) -> Result { + self.is_low().map(|b| !b) + } + fn is_low(&mut self) -> Result { + if self.mode.is_input() { + Ok(self._is_low()) + } else { + Err(PinModeError::IncorrectMode) + } + } +} + +impl StatefulOutputPin for Pin> { #[inline(always)] fn is_set_high(&mut self) -> Result { - self.is_set_low().map(|v| !v) + Ok((*self).is_set_high()) } #[inline(always)] fn is_set_low(&mut self) -> Result { - Ok(unsafe { (*self.port).is_set_low(self.i) }) + Ok((*self).is_set_low()) } } -impl OutputPin for Pin> { +impl OutputPin for Pin> { #[inline(always)] fn set_high(&mut self) -> Result<(), Self::Error> { - unsafe { (*self.port).set_high(self.i) }; + self.set_high(); Ok(()) } #[inline(always)] fn set_low(&mut self) -> Result<(), Self::Error> { - unsafe { (*self.port).set_low(self.i) } + self.set_low(); Ok(()) } } -impl InputPin for Pin> { +impl InputPin for Pin> { #[inline(always)] fn is_high(&mut self) -> Result { - self.is_low().map(|v| !v) + Ok((*self).is_high()) } #[inline(always)] fn is_low(&mut self) -> Result { - Ok(unsafe { (*self.port).is_low(self.i) }) + Ok((*self).is_low()) } } -impl InputPin for Pin> { +impl InputPin for Pin> { #[inline(always)] fn is_high(&mut self) -> Result { - self.is_low().map(|v| !v) + Ok((*self).is_high()) } #[inline(always)] fn is_low(&mut self) -> Result { - Ok(unsafe { (*self.port).is_low(self.i) }) - } -} - -// // PartiallyErasedPin - -// impl ErrorType for PartiallyErasedPin { -// type Error = Infallible; -// } - -// impl OutputPin for PartiallyErasedPin> { -// #[inline(always)] -// fn set_high(&mut self) -> Result<(), Self::Error> { -// self.set_high(); -// Ok(()) -// } - -// #[inline(always)] -// fn set_low(&mut self) -> Result<(), Self::Error> { -// self.set_low(); -// Ok(()) -// } -// } - -// impl StatefulOutputPin for PartiallyErasedPin> { -// #[inline(always)] -// fn is_set_high(&mut self) -> Result { -// Ok((*self).is_set_high()) -// } - -// #[inline(always)] -// fn is_set_low(&mut self) -> Result { -// Ok((*self).is_set_low()) -// } -// } - -// impl InputPin for PartiallyErasedPin> { -// #[inline(always)] -// fn is_high(&mut self) -> Result { -// Ok((*self).is_high()) -// } - -// #[inline(always)] -// fn is_low(&mut self) -> Result { -// Ok((*self).is_low()) -// } -// } - -// impl InputPin for PartiallyErasedPin> { -// #[inline(always)] -// fn is_high(&mut self) -> Result { -// Ok((*self).is_high()) -// } - -// #[inline(always)] -// fn is_low(&mut self) -> Result { -// Ok((*self).is_low()) -// } -// } - -// // ErasedPin - -// impl ErrorType for ErasedPin { -// type Error = core::convert::Infallible; -// } - -// impl OutputPin for ErasedPin> { -// fn set_high(&mut self) -> Result<(), Infallible> { -// self.set_high(); -// Ok(()) -// } - -// fn set_low(&mut self) -> Result<(), Infallible> { -// self.set_low(); -// Ok(()) -// } -// } - -// impl StatefulOutputPin for ErasedPin> { -// fn is_set_high(&mut self) -> Result { -// Ok((*self).is_set_high()) -// } - -// fn is_set_low(&mut self) -> Result { -// Ok((*self).is_set_low()) -// } -// } - -// impl InputPin for ErasedPin> { -// fn is_high(&mut self) -> Result { -// Ok((*self).is_high()) -// } - -// fn is_low(&mut self) -> Result { -// Ok((*self).is_low()) -// } -// } - -// impl InputPin for ErasedPin> { -// fn is_high(&mut self) -> Result { -// Ok((*self).is_high()) -// } - -// fn is_low(&mut self) -> Result { -// Ok((*self).is_low()) -// } -// } + Ok((*self).is_low()) + } +} + +// PartiallyErasedPin + +impl ErrorType for PartiallyErasedPin { + type Error = Infallible; +} + +impl OutputPin for PartiallyErasedPin> { + #[inline(always)] + fn set_high(&mut self) -> Result<(), Self::Error> { + self.set_high(); + Ok(()) + } + + #[inline(always)] + fn set_low(&mut self) -> Result<(), Self::Error> { + self.set_low(); + Ok(()) + } +} + +impl StatefulOutputPin for PartiallyErasedPin> { + #[inline(always)] + fn is_set_high(&mut self) -> Result { + Ok((*self).is_set_high()) + } + + #[inline(always)] + fn is_set_low(&mut self) -> Result { + Ok((*self).is_set_low()) + } +} + +impl InputPin for PartiallyErasedPin> { + #[inline(always)] + fn is_high(&mut self) -> Result { + Ok((*self).is_high()) + } + + #[inline(always)] + fn is_low(&mut self) -> Result { + Ok((*self).is_low()) + } +} + +impl InputPin for PartiallyErasedPin> { + #[inline(always)] + fn is_high(&mut self) -> Result { + Ok((*self).is_high()) + } + + #[inline(always)] + fn is_low(&mut self) -> Result { + Ok((*self).is_low()) + } +} + +// ErasedPin + +impl ErrorType for ErasedPin { + type Error = core::convert::Infallible; +} + +impl OutputPin for ErasedPin> { + fn set_high(&mut self) -> Result<(), Infallible> { + self.set_high(); + Ok(()) + } + + fn set_low(&mut self) -> Result<(), Infallible> { + self.set_low(); + Ok(()) + } +} + +impl StatefulOutputPin for ErasedPin> { + fn is_set_high(&mut self) -> Result { + Ok((*self).is_set_high()) + } + + fn is_set_low(&mut self) -> Result { + Ok((*self).is_set_low()) + } +} + +impl InputPin for ErasedPin> { + fn is_high(&mut self) -> Result { + Ok((*self).is_high()) + } + + fn is_low(&mut self) -> Result { + Ok((*self).is_low()) + } +} + +impl InputPin for ErasedPin> { + fn is_high(&mut self) -> Result { + Ok((*self).is_high()) + } + + fn is_low(&mut self) -> Result { + Ok((*self).is_low()) + } +} diff --git a/src/gpio/partially_erased.rs b/src/gpio/partially_erased.rs new file mode 100644 index 0000000..2d3ab70 --- /dev/null +++ b/src/gpio/partially_erased.rs @@ -0,0 +1,117 @@ +use super::*; + +pub type PEPin = PartiallyErasedPin; + +/// Partially erased pin +/// +/// - `MODE` is one of the pin modes (see [Modes](crate::gpio#modes) section). +/// - `P` is port name: `A` for GPIOA, `B` for GPIOB, etc. +pub struct PartiallyErasedPin { + pin_number: u8, + _mode: PhantomData, +} + +impl PartiallyErasedPin { + pub(crate) fn new(pin_number: u8) -> Self { + Self { + pin_number, + _mode: PhantomData, + } + } +} + +impl PinExt for PartiallyErasedPin { + type Mode = MODE; + + #[inline(always)] + fn pin_id(&self) -> u8 { + self.pin_number + } + + #[inline(always)] + fn port_id(&self) -> u8 { + P as u8 + } +} + +impl PartiallyErasedPin> { + #[inline(always)] + pub fn set_high(&mut self) { + // NOTE(unsafe) atomic write to a stateless register + let gpio = unsafe { &(*gpiox::

()) }; + unsafe { gpio.bsrr.write(|w| w.bits(1 << self.pin_number)) } + } + + #[inline(always)] + pub fn set_low(&mut self) { + // NOTE(unsafe) atomic write to a stateless register + let gpio = unsafe { &(*gpiox::

()) }; + unsafe { gpio.bsrr.write(|w| w.bits(1 << (self.pin_number + 16))) } + } + + #[inline(always)] + pub fn get_state(&self) -> PinState { + if self.is_set_low() { + PinState::Low + } else { + PinState::High + } + } + + #[inline(always)] + pub fn set_state(&mut self, state: PinState) { + match state { + PinState::Low => self.set_low(), + PinState::High => self.set_high(), + } + } + + #[inline(always)] + pub fn is_set_high(&self) -> bool { + !self.is_set_low() + } + + #[inline(always)] + pub fn is_set_low(&self) -> bool { + // NOTE(unsafe) atomic read with no side effects + let gpio = unsafe { &(*gpiox::

()) }; + gpio.odr.read().bits() & (1 << self.pin_number) == 0 + } + + #[inline(always)] + pub fn toggle(&mut self) { + if self.is_set_low() { + self.set_high() + } else { + self.set_low() + } + } +} + +impl PartiallyErasedPin> { + #[inline(always)] + pub fn is_high(&self) -> bool { + !self.is_low() + } + + #[inline(always)] + pub fn is_low(&self) -> bool { + // NOTE(unsafe) atomic read with no side effects + let gpio = unsafe { &(*gpiox::

()) }; + gpio.idr.read().bits() & (1 << self.pin_number) != 0 + } +} + +impl PartiallyErasedPin> { + #[inline(always)] + pub fn is_high(&self) -> bool { + !self.is_low() + } + + #[inline(always)] + pub fn is_low(&self) -> bool { + // NOTE(unsafe) atomic read with no side effects + let gpio = unsafe { &(*gpiox::

()) }; + gpio.idr.read().bits() & (1 << self.pin_number) != 0 + } +} diff --git a/src/lib.rs b/src/lib.rs index a94347c..008e5fd 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -30,6 +30,8 @@ pub mod pwm; #[cfg(feature = "device-selected")] pub mod rcc; #[cfg(feature = "device-selected")] +pub mod rtc; +#[cfg(feature = "device-selected")] pub mod serial; #[cfg(feature = "device-selected")] pub mod spi; diff --git a/src/rcc.rs b/src/rcc.rs index fd0e6d5..a10dd5e 100644 --- a/src/rcc.rs +++ b/src/rcc.rs @@ -5,7 +5,7 @@ use crate::pac::rcc::{ icscr::HSI_FS_A, }; -use crate::pac::{PWR, RCC}; +use crate::pac::{DBG, PWR, RCC}; use crate::time::Hertz; mod enable; @@ -56,6 +56,11 @@ impl APB { let rcc = unsafe { &*RCC::ptr() }; PWR::enable(rcc); } + /// Disable debug clock (DBGEN) bit in RCC_APB1ENR + pub fn disable_dbg() { + let rcc = unsafe { &*RCC::ptr() }; + DBG::disable(rcc); + } } /// MCO source select diff --git a/src/rcc/enable.rs b/src/rcc/enable.rs index d0c326a..f9306b7 100644 --- a/src/rcc/enable.rs +++ b/src/rcc/enable.rs @@ -42,6 +42,7 @@ bus! { GPIOA => (APB, iopenr, ioprstr, 0), GPIOB => (APB, iopenr, ioprstr, 1), I2C => (APB, apbenr1, apbrstr1, 21), + LPTIM => (APB, apbenr1, apbrstr1, 31), PWR => (APB, apbenr1, apbrstr1, 28), SPI1 => (APB, apbenr2, apbrstr2, 12), SYSCFG => (APB, apbenr2, apbrstr2, 0), @@ -64,12 +65,11 @@ bus! { #[cfg(any(feature = "py32f002a", feature = "py32f003", feature = "py32f030"))] bus! { GPIOF => (APB, iopenr, ioprstr, 5), - LPTIM => (APB, apbenr1, apbrstr1, 31), } #[cfg(any(feature = "py32f002b"))] bus! { - LPTIM1 => (APB, apbenr1, apbrstr1, 31), + GPIOC => (APB, iopenr, ioprstr, 2), } #[cfg(any(feature = "py32f030"))] diff --git a/src/rtc.rs b/src/rtc.rs new file mode 100644 index 0000000..c3e5ec6 --- /dev/null +++ b/src/rtc.rs @@ -0,0 +1,399 @@ +/*! + Real time clock +*/ +use crate::pac::{RCC, RTC}; + +use crate::time::Hertz; + +use core::convert::Infallible; +use core::marker::PhantomData; + +// The LSE runs at at 32 768 hertz unless an external clock is provided +const LSE_HERTZ: Hertz = Hertz(32_768); +const LSI_HERTZ: Hertz = Hertz(32_768); + +/// RTC clock source HSE clock divided by 128 (type state) +pub struct RtcClkHseDiv128; +/// RTC clock source LSE oscillator clock (type state) +pub struct RtcClkLse; +/// RTC clock source LSI oscillator clock (type state) +pub struct RtcClkLsi; + +pub enum RestoredOrNewRtc { + Restored(Rtc), + New(Rtc), +} + +/** +Real time clock + +A continuously running clock that counts seconds¹. It can optionally +be enabled during Sleep or Stop mode so that the counter is not affected by +these modes.This allows it to be used to wake the +CPU when it is in low power mode. + + + See [examples/rtc.rs] and [examples/blinky_rtc.rs] for usage examples. + + 1: Unless configured to another frequency using [select_frequency](struct.Rtc.html#method.select_frequency) + + [examples/rtc.rs]: https://github.com/py32f0xx-hal/blob/v0.2.0/examples/rtc.rs + [examples/blinky_rtc.rs]: https://github.com/py32f0xx-hal/blob/v0.2.0/examples/blinky_rtc.rs +*/ + +pub struct Rtc { + regs: RTC, + _clock_source: PhantomData, +} + +impl Rtc { + /** + Initialises the RTC with low-speed external crystal source (lse). + + The frequency is set to 1 Hz. + + In case application is running off a battery on VBAT, + this method will reset the RTC every time, leading to lost time, + you may want to use + [`restore_or_new`](Rtc::::restore_or_new) instead. + */ + pub fn new(regs: RTC) -> Self { + let mut result = Rtc { + regs, + _clock_source: PhantomData, + }; + + Self::enable_rtc(); + + // Set the prescaler to make it count up once every second. + let prl = LSE_HERTZ.0 - 1; + assert!(prl < 1 << 20); + result.perform_write(|s| { + s.regs.prlh.write(|w| unsafe { w.bits(prl >> 16) }); + s.regs.prll.write(|w| unsafe { w.bits(prl as u16 as u32) }); + }); + + result + } + + /// Tries to obtain currently running RTC to prevent a reset in case it was running from VBAT. + /// If the RTC is not running, or is not LSE, it will be reinitialized. + /// + /// # Examples + /// ``` + /// let rtc = match Rtc::restore_or_new(p.RTC, &mut backup_domain) { + /// Restored(rtc) => rtc, // The rtc is restored from previous configuration. You may verify the frequency you want if needed. + /// New(rtc) => { // The rtc was just initialized, the clock source selected, frequency is 1.Hz() + /// // Initialize rtc with desired parameters + /// rtc.select_frequency(2u16.Hz()); // Set the frequency to 2 Hz. This will stay same after reset + /// rtc + /// } + /// }; + /// ``` + pub fn restore_or_new(regs: RTC) -> RestoredOrNewRtc { + if !Self::is_enabled() { + RestoredOrNewRtc::New(Rtc::new(regs)) + } else { + RestoredOrNewRtc::Restored(Rtc { + regs, + _clock_source: PhantomData, + }) + } + } + + /// Returns whether the RTC is currently enabled and LSE is selected. + fn is_enabled() -> bool { + let rcc = unsafe { &*RCC::ptr() }; + let bdcr = rcc.bdcr.read(); + bdcr.rtcen().is_enabled() && bdcr.rtcsel().is_lse() + } + + /// Enables the RTC device with the lse as the clock + fn enable_rtc() { + // NOTE: Safe RCC access because we are only accessing bdcr + // and we have a &mut on BackupDomain + let rcc = unsafe { &*RCC::ptr() }; + rcc.bdcr.modify(|_, w| { + // start the LSE oscillator + w.lseon().set_bit(); + // Enable the RTC + w.rtcen().set_bit(); + // Set the source of the RTC to LSE + w.rtcsel().lse() + }) + } +} + +impl Rtc { + /** + Initialises the RTC with low-speed internal oscillator source (lsi). + + The frequency is set to 1 Hz. + + In case application is running of a battery on VBAT, + this method will reset the RTC every time, leading to lost time, + you may want to use + [`restore_or_new_lsi`](Rtc::::restore_or_new_lsi) instead. + */ + pub fn new_lsi(regs: RTC) -> Self { + let mut result = Rtc { + regs, + _clock_source: PhantomData, + }; + + Self::enable_rtc(); + + // Set the prescaler to make it count up once every second. + let prl = LSI_HERTZ.0 - 1; + assert!(prl < 1 << 20); + result.perform_write(|s| { + s.regs.prlh.write(|w| unsafe { w.bits(prl >> 16) }); + s.regs.prll.write(|w| unsafe { w.bits(prl as u16 as u32) }); + }); + + result + } + + /// Tries to obtain currently running RTC to prevent reset in case it was running from VBAT. + /// If the RTC is not running, or is not LSI, it will be reinitialized. + pub fn restore_or_new_lsi(regs: RTC) -> RestoredOrNewRtc { + if !Rtc::::is_enabled() { + RestoredOrNewRtc::New(Rtc::new_lsi(regs)) + } else { + RestoredOrNewRtc::Restored(Rtc { + regs, + _clock_source: PhantomData, + }) + } + } + + /// Returns whether the RTC is currently enabled and LSI is selected. + fn is_enabled() -> bool { + let rcc = unsafe { &*RCC::ptr() }; + rcc.bdcr.read().rtcen().bit() && rcc.bdcr.read().rtcsel().is_lsi() + } + + /// Enables the RTC device with the lsi as the clock + fn enable_rtc() { + // NOTE: Safe RCC access because we are only accessing bdcr + // and we have a &mut on BackupDomain + let rcc = unsafe { &*RCC::ptr() }; + rcc.csr.modify(|_, w| { + // start the LSI oscillator + w.lsion().set_bit() + }); + rcc.bdcr.modify(|_, w| { + // Enable the RTC + w.rtcen().set_bit(); + // Set the source of the RTC to LSI + w.rtcsel().lsi() + }) + } +} + +impl Rtc { + /** + Initialises the RTC with high-speed external oscillator source (hse) + divided by 128. + + The frequency is set to 1 Hz. + + In case application is running of a battery on VBAT, + this method will reset the RTC every time, leading to lost time, + you may want to use + [`restore_or_new_hse`](Rtc::::restore_or_new_hse) instead. + */ + pub fn new_hse(regs: RTC, hse: Hertz) -> Self { + let mut result = Rtc { + regs, + _clock_source: PhantomData, + }; + + Self::enable_rtc(); + + // Set the prescaler to make it count up once every second. + let prl = hse.0 / 128 - 1; + assert!(prl < 1 << 20); + result.perform_write(|s| { + s.regs.prlh.write(|w| unsafe { w.bits(prl >> 16) }); + s.regs.prll.write(|w| unsafe { w.bits(prl as u16 as u32) }); + }); + + result + } + + /// Tries to obtain currently running RTC to prevent reset in case it was running from VBAT. + /// If the RTC is not running, or is not HSE, it will be reinitialized. + pub fn restore_or_new_hse(regs: RTC, hse: Hertz) -> RestoredOrNewRtc { + if !Self::is_enabled() { + RestoredOrNewRtc::New(Rtc::new_hse(regs, hse)) + } else { + RestoredOrNewRtc::Restored(Rtc { + regs, + _clock_source: PhantomData, + }) + } + } + + fn is_enabled() -> bool { + let rcc = unsafe { &*RCC::ptr() }; + let bdcr = rcc.bdcr.read(); + bdcr.rtcen().is_enabled() && bdcr.rtcsel().is_hse() + } + + /// Enables the RTC device with the lsi as the clock + fn enable_rtc() { + // NOTE: Safe RCC access because we are only accessing bdcr + // and we have a &mut on BackupDomain + let rcc = unsafe { &*RCC::ptr() }; + if rcc.cr.read().hserdy().bit_is_clear() { + panic!("HSE oscillator not ready"); + } + rcc.bdcr.modify(|_, w| { + // Enable the RTC + w.rtcen().set_bit(); + // Set the source of the RTC to HSE/128 + w.rtcsel().hse() + }) + } +} + +impl Rtc { + /// Selects the frequency of the RTC Timer + /// NOTE: Maximum frequency of 16384 Hz using the internal LSE + pub fn select_frequency(&mut self, frequency: Hertz) { + // The manual says that the zero value for the prescaler is not recommended, thus the + // minimum division factor is 2 (prescaler + 1) + assert!(frequency.0 <= LSE_HERTZ.0 / 2); + + let prescaler = LSE_HERTZ.0 / frequency.0 - 1; + self.perform_write(|s| { + s.regs.prlh.write(|w| unsafe { w.bits(prescaler >> 16) }); + s.regs + .prll + .write(|w| unsafe { w.bits(prescaler as u16 as u32) }); + }); + } + + /// Set the current RTC counter value to the specified amount + pub fn set_time(&mut self, counter_value: u32) { + self.perform_write(|s| { + s.regs + .cnth + .write(|w| unsafe { w.bits(counter_value >> 16) }); + s.regs + .cntl + .write(|w| unsafe { w.bits(counter_value as u16 as u32) }); + }); + } + + /** + Sets the time at which an alarm will be triggered + + This also clears the alarm flag if it is set + */ + pub fn set_alarm(&mut self, counter_value: u32) { + // Set alarm time + // See section 18.3.5 for explanation + let alarm_value = counter_value - 1; + + // TODO: Remove this `allow` once these fields are made safe for stm32f100 + #[allow(unused_unsafe)] + self.perform_write(|s| { + s.regs + .alrh + .write(|w| unsafe { w.alrh().bits((alarm_value >> 16) as u16) }); + s.regs + .alrl + .write(|w| unsafe { w.alrl().bits(alarm_value as u16) }); + }); + + self.clear_alarm_flag(); + } + + /// Enables the RTC interrupt to trigger when the counter reaches the alarm value. In addition, + /// if the EXTI controller has been set up correctly, this function also enables the RTCALARM + /// interrupt. + pub fn listen_alarm(&mut self) { + // Enable alarm interrupt + self.perform_write(|s| { + s.regs.crh.modify(|_, w| w.alrie().set_bit()); + }) + } + + /// Stops the RTC alarm from triggering the RTC and RTCALARM interrupts + pub fn unlisten_alarm(&mut self) { + // Disable alarm interrupt + self.perform_write(|s| { + s.regs.crh.modify(|_, w| w.alrie().clear_bit()); + }) + } + + /// Reads the current counter + pub fn current_time(&self) -> u32 { + // 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() + } + + /// Enables triggering the RTC interrupt every time the RTC counter is increased + pub fn listen_seconds(&mut self) { + self.perform_write(|s| s.regs.crh.modify(|_, w| w.secie().set_bit())) + } + + /// Disables the RTC second interrupt + pub fn unlisten_seconds(&mut self) { + self.perform_write(|s| s.regs.crh.modify(|_, w| w.secie().clear_bit())) + } + + /// Clears the RTC second interrupt flag + pub fn clear_second_flag(&mut self) { + self.perform_write(|s| s.regs.crl.modify(|_, w| w.secf().clear_bit())) + } + + /// Clears the RTC alarm interrupt flag + pub fn clear_alarm_flag(&mut self) { + self.perform_write(|s| s.regs.crl.modify(|_, w| w.alrf().clear_bit())) + } + + /** + Return `Ok(())` if the alarm flag is set, `Err(nb::WouldBlock)` otherwise. + + ```rust + use nb::block; + + rtc.set_alarm(rtc.read_counts() + 5); + // NOTE: Safe unwrap because Infallible can't be returned + block!(rtc.wait_alarm()).unwrap(); + ``` + */ + pub fn wait_alarm(&mut self) -> nb::Result<(), Infallible> { + if self.regs.crl.read().alrf().bit() { + self.regs.crl.modify(|_, w| w.alrf().clear_bit()); + Ok(()) + } else { + Err(nb::Error::WouldBlock) + } + } + + /** + The RTC registers can not be written to at any time as documented on page + 350 of the manual. Performing writes using this function ensures that + the writes are done correctly. + */ + fn perform_write(&mut self, func: impl Fn(&mut Self)) { + // Wait for the last write operation to be done + while !self.regs.crl.read().rtoff().bit() {} + // Put the clock into config mode + self.regs.crl.modify(|_, w| w.cnf().set_bit()); + + // Perform the write operation + func(self); + + // Take the device out of config mode + self.regs.crl.modify(|_, w| w.cnf().clear_bit()); + // Wait for the write to be done + while !self.regs.crl.read().rtoff().bit() {} + } +} diff --git a/src/serial.rs b/src/serial.rs index 216d253..caaae9b 100644 --- a/src/serial.rs +++ b/src/serial.rs @@ -58,8 +58,6 @@ use core::marker::PhantomData; use core::ops::Deref; -use core::sync::atomic::{self, Ordering}; -use embedded_dma::{ReadBuffer, WriteBuffer}; #[cfg(feature = "with-dma")] use crate::dma::{ @@ -71,6 +69,10 @@ use crate::gpio::{Alternate, AF1}; use crate::pac::{self, RCC}; use crate::rcc::{BusClock, Clocks, Enable, Reset}; use crate::time::{Bps, U32Ext}; +#[cfg(feature = "with-dma")] +use core::sync::atomic::{self, Ordering}; +#[cfg(feature = "with-dma")] +use embedded_dma::{ReadBuffer, WriteBuffer}; #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] use crate::gpio::{gpiof::*, AF0, AF8}; @@ -793,6 +795,7 @@ pub type Rx2 = Rx; #[cfg(any(feature = "py32f003", feature = "py32f030",))] pub type Tx2 = Tx; +#[cfg(feature = "with-dma")] macro_rules! serialdmarx { ($USARTX:ty: ($dmaX:ty, $dmamux:expr, { $($rxdma:ident: $ch:literal,)+ @@ -931,6 +934,7 @@ serialdmarx! { }), } +#[cfg(feature = "with-dma")] macro_rules! serialdmatx { ($USARTX:ty: ($dmaX:ty, $dmamux:expr, { $($txdma:ident: $ch:literal,)+ diff --git a/src/spi.rs b/src/spi.rs index 7261709..4cf3670 100644 --- a/src/spi.rs +++ b/src/spi.rs @@ -43,8 +43,9 @@ use core::marker::PhantomData; use core::ops::{Deref, DerefMut}; use core::ptr; +#[cfg(feature = "with-dma")] use core::sync::atomic::{self, Ordering}; - +#[cfg(feature = "with-dma")] use embedded_dma::{ReadBuffer, WriteBuffer}; use crate::pac::{self, RCC}; From bbc1fd484858dfc0d746b8036fef2b9a7137646d Mon Sep 17 00:00:00 2001 From: Greg Green Date: Tue, 17 Dec 2024 10:12:17 -0800 Subject: [PATCH 07/11] Added timer module and submodules Deleted timers and delay modules, functionality in new modules time module converted to use fugit All code converted to use fugit rates instead of old time module functions --- CHANGELOG.md | 6 +- Cargo.toml | 10 + examples/adc_values.rs | 2 +- examples/blinky.rs | 2 +- examples/blinky_adc.rs | 6 +- examples/blinky_delay.rs | 6 +- examples/blinky_multiple.rs | 6 +- examples/blinky_timer.rs | 12 +- examples/blinky_timer_irq.rs | 19 +- examples/exti.rs | 2 +- examples/flash_systick.rs | 2 +- examples/flash_systick_fancier.rs | 2 +- examples/i2c_find_address.rs | 6 +- examples/led_hal_button_irq.rs | 8 +- examples/pwm.rs | 4 +- examples/pwm_complementary.rs | 8 +- examples/serial_echo.rs | 2 +- examples/serial_spi_bridge.rs | 2 +- examples/serial_stopwatch.rs | 12 +- examples/spi_hal_apa102c.rs | 2 +- examples/spi_rc522.rs | 11 +- examples/watchdog.rs | 8 +- src/adc.rs | 19 +- src/delay.rs | 125 ------- src/dma.rs | 1 + src/gpio.rs | 45 ++- src/i2c.rs | 13 +- src/lib.rs | 4 +- src/prelude.rs | 4 + src/pwm.rs | 22 +- src/rcc.rs | 38 +- src/rcc/enable.rs | 6 +- src/rtc.rs | 16 +- src/serial.rs | 3 +- src/spi.rs | 3 +- src/time.rs | 129 ++++--- src/timer.rs | 565 ++++++++++++++++++++++++++++++ src/timer/counter.rs | 374 ++++++++++++++++++++ src/timer/delay.rs | 214 +++++++++++ src/timer/hal_02.rs | 306 ++++++++++++++++ src/timer/hal_1.rs | 47 +++ src/timer/monotonic.rs | 153 ++++++++ src/timer/pins.rs | 112 ++++++ src/timers.rs | 351 ------------------- src/watchdog.rs | 8 +- 45 files changed, 2048 insertions(+), 648 deletions(-) delete mode 100644 src/delay.rs create mode 100644 src/timer.rs create mode 100644 src/timer/counter.rs create mode 100644 src/timer/delay.rs create mode 100644 src/timer/hal_02.rs create mode 100644 src/timer/hal_1.rs create mode 100644 src/timer/monotonic.rs create mode 100644 src/timer/pins.rs delete mode 100644 src/timers.rs diff --git a/CHANGELOG.md b/CHANGELOG.md index 159a730..393dc91 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -24,7 +24,9 @@ This version depends on py32-rs v1.1.2 or later * `as_floating_input` * `as_pull_up_input` * `as_pull_down_input` -- module `rcc` has new traits and implementations `Enable`, `Reset`, `BusClock`, `BusTimerClock`, `RccBus` +- module `rcc` + * new traits and implementations `Enable`, `Reset`, `BusClock`, `BusTimerClock`, `RccBus` + * added function `debug_stop_mode` for control of clock function in sleep and stop conditions - added module `rtc` and examples thereof - module `serial` * Implemented embedded-hal v1.0 nb::Read/Write traits @@ -59,6 +61,7 @@ This version depends on py32-rs v1.1.2 or later - module `spi` * embedded-hal v0.2.7 trait implementations moved to spi/hal_02 module * changed to use rcc enable, reset, and bus frequencies +- module `time` changed to use fugit crate, this alters how you specify frequency, ie, hz -> Hz, etc. - module `timers` * changed to use rcc enable, reset, and bus frequencies @@ -66,6 +69,7 @@ This version depends on py32-rs v1.1.2 or later ### Removed +- `delay` and `timers` modules removed, the functionality is in the `timer` module now - `spi::Event::Crc` removed, as that doesn't exist on this micro ### Fixed diff --git a/Cargo.toml b/Cargo.toml index ee6e520..aac4ce7 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -29,6 +29,11 @@ embedded-time = "0.12.1" embedded-dma = "0.2.0" nb = "1.1.0" void = { version = "1.0.2", default-features = false } +defmt = { version = "0.3.8", optional = true } +bitflags = "1.3.2" +fugit = "0.3.7" +fugit-timer = "0.1.3" +rtic-monotonic = { version = "1.0", optional = true } [dependencies.embedded-hal-02] package = "embedded-hal" @@ -65,6 +70,8 @@ py32f003 = ["py32f0/py32f003", "device-selected", "with-dma"] py32f002a = ["py32f0/py32f002a", "device-selected"] py32f002b = ["py32f0/py32f002b", "device-selected"] +defmt = ["dep:defmt"] + # Features based on Flash size (in kbytes) flash-16 = [] flash-20 = [] @@ -100,6 +107,9 @@ py32f003xx8 = ["py32f003", "flash-64", "ram-8"] py32f002ax5 = ["py32f002a", "flash-20", "ram-3"] py32f002bx5 = ["py32f002b", "flash-24", "ram-3"] +# rtic os +rtic = ["dep:rtic-monotonic"] + [profile.dev] debug = true lto = true diff --git a/examples/adc_values.rs b/examples/adc_values.rs index 6897f9a..239a4b3 100644 --- a/examples/adc_values.rs +++ b/examples/adc_values.rs @@ -31,7 +31,7 @@ fn main() -> ! { ) { cortex_m::interrupt::free(move |cs| { let mut flash = dp.FLASH; - let rcc = dp.RCC.configure().sysclk(24.mhz()).freeze(&mut flash); + let rcc = dp.RCC.configure().sysclk(24.MHz()).freeze(&mut flash); let gpioa = dp.GPIOA.split(); diff --git a/examples/blinky.rs b/examples/blinky.rs index 9ad9825..20b1df0 100644 --- a/examples/blinky.rs +++ b/examples/blinky.rs @@ -12,7 +12,7 @@ use cortex_m_rt::entry; #[entry] fn main() -> ! { if let Some(mut p) = pac::Peripherals::take() { - let _rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); + let _rcc = p.RCC.configure().sysclk(8.MHz()).freeze(&mut p.FLASH); let gpioa = p.GPIOA.split(); diff --git a/examples/blinky_adc.rs b/examples/blinky_adc.rs index f3f48fb..4b3329f 100644 --- a/examples/blinky_adc.rs +++ b/examples/blinky_adc.rs @@ -5,7 +5,7 @@ use panic_halt as _; use py32f0xx_hal as hal; -use crate::hal::{adc::Adc, delay::Delay, pac, prelude::*}; +use crate::hal::{adc::Adc, pac, prelude::*}; use cortex_m::peripheral::Peripherals; use cortex_m_rt::entry; @@ -15,7 +15,7 @@ use embedded_hal_02::blocking::delay::DelayMs; #[entry] fn main() -> ! { if let (Some(mut p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { - let rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); + let rcc = p.RCC.configure().sysclk(8.MHz()).freeze(&mut p.FLASH); let gpioa = p.GPIOA.split(); @@ -25,7 +25,7 @@ fn main() -> ! { let mut an_in = gpioa.pa0.into_analog(); // Get delay provider - let mut delay = Delay::new(cp.SYST, &rcc); + let mut delay = cp.SYST.delay(&rcc.clocks); // Get access to the ADC let mut adc = Adc::new(p.ADC, hal::adc::AdcClockMode::Pclk); diff --git a/examples/blinky_delay.rs b/examples/blinky_delay.rs index 49ead16..5825325 100644 --- a/examples/blinky_delay.rs +++ b/examples/blinky_delay.rs @@ -5,7 +5,7 @@ use panic_halt as _; use py32f0xx_hal as hal; -use crate::hal::{delay::Delay, pac, prelude::*}; +use crate::hal::{pac, prelude::*}; use cortex_m::peripheral::Peripherals; use cortex_m_rt::entry; use embedded_hal_02::blocking::delay::DelayMs; @@ -13,7 +13,7 @@ use embedded_hal_02::blocking::delay::DelayMs; #[entry] fn main() -> ! { if let (Some(mut p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { - let rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); + let rcc = p.RCC.configure().sysclk(8.MHz()).freeze(&mut p.FLASH); let gpioa = p.GPIOA.split(); @@ -21,7 +21,7 @@ fn main() -> ! { let mut led = gpioa.pa5.into_push_pull_output(); // Get delay provider - let mut delay = Delay::new(cp.SYST, &rcc); + let mut delay = cp.SYST.delay(&rcc.clocks); loop { led.toggle(); diff --git a/examples/blinky_multiple.rs b/examples/blinky_multiple.rs index d7ec248..f19f983 100644 --- a/examples/blinky_multiple.rs +++ b/examples/blinky_multiple.rs @@ -5,7 +5,7 @@ use panic_halt as _; use py32f0xx_hal as hal; -use crate::hal::{delay::Delay, pac, prelude::*}; +use crate::hal::{pac, prelude::*}; use cortex_m::peripheral::Peripherals; use cortex_m_rt::entry; @@ -14,7 +14,7 @@ use embedded_hal_02::blocking::delay::DelayMs; #[entry] fn main() -> ! { if let (Some(mut p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { - let rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); + let rcc = p.RCC.configure().sysclk(8.MHz()).freeze(&mut p.FLASH); let gpioa = p.GPIOA.split(); let gpiob = p.GPIOB.split(); @@ -25,7 +25,7 @@ fn main() -> ! { let led2 = gpiob.pb1.into_push_pull_output(); // Get delay provider - let mut delay = Delay::new(cp.SYST, &rcc); + let mut delay = cp.SYST.delay(&rcc.clocks); // Store them together after erasing the type let mut leds = [led1.erase(), led2.erase()]; diff --git a/examples/blinky_timer.rs b/examples/blinky_timer.rs index cd1cc2d..2d3d48e 100644 --- a/examples/blinky_timer.rs +++ b/examples/blinky_timer.rs @@ -5,24 +5,22 @@ use panic_halt as _; use py32f0xx_hal as hal; -use crate::hal::{pac, prelude::*, time::Hertz, timers::*}; - +use crate::hal::{pac, prelude::*}; use cortex_m_rt::entry; -use embedded_hal_02::timer::CountDown; - #[entry] fn main() -> ! { if let Some(mut p) = pac::Peripherals::take() { - let rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); + let rcc = p.RCC.configure().sysclk(8.MHz()).freeze(&mut p.FLASH); let gpioa = p.GPIOA.split(); // (Re-)configure PA5 as output let mut led = gpioa.pa5.into_push_pull_output(); - // Set up a timer expiring after 1s - let mut timer = Timer::tim1(p.TIM1, Hertz(5), &rcc.clocks); + // Set up a timer expiring after 200ms + let mut timer = p.TIM1.counter_hz(&rcc.clocks); + timer.start(5.Hz()).unwrap(); loop { led.toggle(); diff --git a/examples/blinky_timer_irq.rs b/examples/blinky_timer_irq.rs index 6c56087..f18c7b6 100644 --- a/examples/blinky_timer_irq.rs +++ b/examples/blinky_timer_irq.rs @@ -9,14 +9,12 @@ use crate::hal::{ gpio::{gpioa, Output, PushPull}, pac::{interrupt, Interrupt, Peripherals, TIM16}, prelude::*, - time::Hertz, - timers::*, + timer::*, }; use core::cell::RefCell; use cortex_m::{interrupt::Mutex, peripheral::Peripherals as c_m_Peripherals}; use cortex_m_rt::entry; -use embedded_hal_02::timer::CountDown; // A type definition for the GPIO pin to be used for our LED type LEDPIN = gpioa::PA5>; @@ -25,14 +23,14 @@ type LEDPIN = gpioa::PA5>; static GLED: Mutex>> = Mutex::new(RefCell::new(None)); // Make timer interrupt registers globally available -static GINT: Mutex>>> = Mutex::new(RefCell::new(None)); +static GINT: Mutex>>> = Mutex::new(RefCell::new(None)); // Define an interupt handler, i.e. function to call when interrupt occurs. Here if our external // interrupt trips when the timer timed out #[interrupt] fn TIM16() { static mut LED: Option = None; - static mut INT: Option> = None; + static mut INT: Option> = None; let led = LED.get_or_insert_with(|| { cortex_m::interrupt::free(|cs| { @@ -43,7 +41,7 @@ fn TIM16() { let int = INT.get_or_insert_with(|| { cortex_m::interrupt::free(|cs| { - // Move LED pin here, leaving a None in its place + // Move timer here, leaving a None in its place GINT.borrow(cs).replace(None).unwrap() }) }); @@ -59,8 +57,8 @@ fn main() -> ! { let rcc = p .RCC .configure() - .sysclk(24.mhz()) - .pclk(24.mhz()) + .sysclk(24.MHz()) + .pclk(24.MHz()) .freeze(&mut p.FLASH); let gpioa = p.GPIOA.split(); @@ -72,10 +70,11 @@ fn main() -> ! { *GLED.borrow(cs).borrow_mut() = Some(led); // Set up a timer expiring after 1s - let mut timer = Timer::tim16(p.TIM16, Hertz(10), &rcc.clocks); + let mut timer = p.TIM16.counter_hz(&rcc.clocks); // Generate an interrupt when the timer expires - timer.listen(Event::TimeOut); + timer.listen(Event::Update); + timer.start(1.Hz()).unwrap(); // Move the timer into our global storage *GINT.borrow(cs).borrow_mut() = Some(timer); diff --git a/examples/exti.rs b/examples/exti.rs index b1adb42..a1dfa3a 100644 --- a/examples/exti.rs +++ b/examples/exti.rs @@ -42,7 +42,7 @@ fn main() -> ! { // initialization phase let mut p = pac::Peripherals::take().unwrap(); let _cp = cortex_m::peripheral::Peripherals::take().unwrap(); - let _rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut p.FLASH); + let _rcc = p.RCC.configure().sysclk(8.MHz()).freeze(&mut p.FLASH); { // the scope ensures that the int_pin reference is dropped before the first ISR can be executed. diff --git a/examples/flash_systick.rs b/examples/flash_systick.rs index d3c7e5e..56c0d3b 100644 --- a/examples/flash_systick.rs +++ b/examples/flash_systick.rs @@ -23,7 +23,7 @@ static GPIO: Mutex>>>> = Mutex::new(R fn main() -> ! { if let (Some(mut p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { cortex_m::interrupt::free(move |cs| { - let _rcc = p.RCC.configure().sysclk(24.mhz()).freeze(&mut p.FLASH); + let _rcc = p.RCC.configure().sysclk(24.MHz()).freeze(&mut p.FLASH); let gpioa = p.GPIOA.split(); diff --git a/examples/flash_systick_fancier.rs b/examples/flash_systick_fancier.rs index 7174c37..1a5100b 100644 --- a/examples/flash_systick_fancier.rs +++ b/examples/flash_systick_fancier.rs @@ -23,7 +23,7 @@ static GPIO: Mutex>> = Mutex::new(RefCell::new(None)); fn main() -> ! { if let (Some(mut p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { cortex_m::interrupt::free(move |cs| { - let _rcc = p.RCC.configure().sysclk(24.mhz()).freeze(&mut p.FLASH); + let _rcc = p.RCC.configure().sysclk(24.MHz()).freeze(&mut p.FLASH); // Get access to individual pins in the GPIO port let gpioa = p.GPIOA.split(); diff --git a/examples/i2c_find_address.rs b/examples/i2c_find_address.rs index fafe272..5ee86bb 100644 --- a/examples/i2c_find_address.rs +++ b/examples/i2c_find_address.rs @@ -22,8 +22,8 @@ fn main() -> ! { let rcc = p .RCC .configure() - .sysclk(24.mhz()) - .pclk(24.mhz()) + .sysclk(24.MHz()) + .pclk(24.MHz()) .freeze(&mut flash); let gpioa = p.GPIOA.split(); @@ -33,7 +33,7 @@ fn main() -> ! { let sda = gpioa.pa2.into_alternate_af12(); // Configure I2C with 100kHz rate - let mut i2c = I2c::i2c(p.I2C, (scl, sda), 100.khz(), &rcc.clocks); + let mut i2c = I2c::i2c(p.I2C, (scl, sda), 100.kHz(), &rcc.clocks); let mut devices = 0; // I2C addresses are 7-bit wide, covering the 0-127 range diff --git a/examples/led_hal_button_irq.rs b/examples/led_hal_button_irq.rs index e84fa27..3469e9f 100644 --- a/examples/led_hal_button_irq.rs +++ b/examples/led_hal_button_irq.rs @@ -6,10 +6,10 @@ use panic_halt as _; use py32f0xx_hal as hal; use crate::hal::{ - delay::Delay, gpio::*, pac::{interrupt, Interrupt, Peripherals, EXTI}, prelude::*, + timer::SysDelay, }; use cortex_m::{interrupt::Mutex, peripheral::Peripherals as c_m_Peripherals}; @@ -22,7 +22,7 @@ use embedded_hal_02::blocking::delay::DelayMs; static LED: Mutex>>>> = Mutex::new(RefCell::new(None)); // Make our delay provider globally available -static DELAY: Mutex>> = Mutex::new(RefCell::new(None)); +static DELAY: Mutex>> = Mutex::new(RefCell::new(None)); // Make external interrupt registers globally available static INT: Mutex>> = Mutex::new(RefCell::new(None)); @@ -36,7 +36,7 @@ fn main() -> ! { rcc.apbenr2.modify(|_, w| w.syscfgen().set_bit()); let mut flash = p.FLASH; - let rcc = rcc.configure().sysclk(8.mhz()).freeze(&mut flash); + let rcc = rcc.configure().sysclk(8.MHz()).freeze(&mut flash); let gpioa = p.GPIOA.split(); let gpiob = p.GPIOB.split(); @@ -52,7 +52,7 @@ fn main() -> ! { led.set_low(); // Initialise delay provider - let delay = Delay::new(cp.SYST, &rcc); + let delay = cp.SYST.delay(&rcc.clocks); // Enable external interrupt for PB2 exti.exticr1.modify(|_, w| w.exti2().pb()); diff --git a/examples/pwm.rs b/examples/pwm.rs index 659783a..14ff5d3 100644 --- a/examples/pwm.rs +++ b/examples/pwm.rs @@ -16,7 +16,7 @@ use hal::{pac, prelude::*, pwm}; fn main() -> ! { if let Some(mut dp) = pac::Peripherals::take() { // Set up the system clock. - let rcc = dp.RCC.configure().sysclk(8.mhz()).freeze(&mut dp.FLASH); + let rcc = dp.RCC.configure().sysclk(8.MHz()).freeze(&mut dp.FLASH); let gpioa = dp.GPIOA.split(); let channels = ( @@ -24,7 +24,7 @@ fn main() -> ! { gpioa.pa9.into_alternate_af2(), // on TIM1_CH2 ); - let pwm = pwm::tim1(dp.TIM1, channels, &rcc.clocks, 20u32.khz()); + let pwm = pwm::tim1(dp.TIM1, channels, &rcc.clocks, 20.kHz()); let (mut ch1, mut ch2) = pwm; let max_duty = ch1.get_max_duty(); ch1.set_duty(max_duty / 2); diff --git a/examples/pwm_complementary.rs b/examples/pwm_complementary.rs index c553625..038d130 100644 --- a/examples/pwm_complementary.rs +++ b/examples/pwm_complementary.rs @@ -12,13 +12,13 @@ use py32f0xx_hal as hal; use embedded_hal_02::blocking::delay::DelayMs; use embedded_hal_02::PwmPin; -use hal::{delay::Delay, pac, prelude::*, pwm}; +use hal::{pac, prelude::*, pwm}; #[entry] fn main() -> ! { if let Some(mut dp) = pac::Peripherals::take() { // Set up the system clock. - let rcc = dp.RCC.configure().sysclk(8.mhz()).freeze(&mut dp.FLASH); + let rcc = dp.RCC.configure().sysclk(8.MHz()).freeze(&mut dp.FLASH); let gpioa = dp.GPIOA.split(); let channels = ( @@ -26,7 +26,7 @@ fn main() -> ! { gpioa.pa7.into_alternate_af2(), // on TIM1_CH1N ); - let pwm = pwm::tim1(dp.TIM1, channels, &rcc.clocks, 20u32.khz()); + let pwm = pwm::tim1(dp.TIM1, channels, &rcc.clocks, 20.kHz()); let (mut ch1, mut ch1n) = pwm; let max_duty = ch1.get_max_duty(); ch1.set_duty(max_duty / 2); @@ -35,7 +35,7 @@ fn main() -> ! { // simple duty sweep if let Some(cp) = cortex_m::Peripherals::take() { - let mut delay = Delay::new(cp.SYST, &rcc); + let mut delay = cp.SYST.delay(&rcc.clocks); let steps = 100; diff --git a/examples/serial_echo.rs b/examples/serial_echo.rs index b8f9416..abf1fa8 100644 --- a/examples/serial_echo.rs +++ b/examples/serial_echo.rs @@ -24,7 +24,7 @@ fn main() -> ! { .RCC .configure() .hsi(HSIFreq::Freq24mhz) - .sysclk(24.mhz()) + .sysclk(24.MHz()) .freeze(&mut flash); rcc.configure_mco(MCOSrc::Sysclk, MCODiv::NotDivided); diff --git a/examples/serial_spi_bridge.rs b/examples/serial_spi_bridge.rs index b2c5893..0c010e1 100644 --- a/examples/serial_spi_bridge.rs +++ b/examples/serial_spi_bridge.rs @@ -49,7 +49,7 @@ fn main() -> ! { let mut spi = p.SPI1.spi( (Some(sck), Some(miso), Some(mosi)), MODE, - 1.mhz().into(), + 1.MHz().into(), &rcc.clocks, ); diff --git a/examples/serial_stopwatch.rs b/examples/serial_stopwatch.rs index 5b281c5..6fbae54 100644 --- a/examples/serial_stopwatch.rs +++ b/examples/serial_stopwatch.rs @@ -8,17 +8,16 @@ use py32f0xx_hal as hal; use crate::hal::{ pac::{interrupt, Interrupt, Peripherals, TIM16}, prelude::*, - timers::{Event, Timer}, + timer::{CounterMs, Event}, }; use core::cell::RefCell; use core::fmt::Write as _; use core::ops::DerefMut; use cortex_m::{interrupt::Mutex, peripheral::Peripherals as c_m_Peripherals}; use cortex_m_rt::entry; -use embedded_hal_02::timer::CountDown; // Make timer interrupt registers globally available -static GINT: Mutex>>> = Mutex::new(RefCell::new(None)); +static GINT: Mutex>>> = Mutex::new(RefCell::new(None)); #[derive(Copy, Clone)] struct Time { @@ -58,7 +57,7 @@ fn main() -> ! { if let (Some(p), Some(cp)) = (Peripherals::take(), c_m_Peripherals::take()) { let mut serial = cortex_m::interrupt::free(move |cs| { let mut flash = p.FLASH; - let rcc = p.RCC.configure().sysclk(24.mhz()).freeze(&mut flash); + let rcc = p.RCC.configure().sysclk(24.MHz()).freeze(&mut flash); // Use USART1 with PA2 and PA3 as serial port let gpioa = p.GPIOA.split(); @@ -66,10 +65,11 @@ fn main() -> ! { let rx = gpioa.pa3.into_alternate_af1(); // Set up a timer expiring every millisecond - let mut timer = Timer::tim16(p.TIM16, 1000.hz(), &rcc.clocks); + let mut timer = p.TIM16.counter_ms(&rcc.clocks); // Generate an interrupt when the timer expires - timer.listen(Event::TimeOut); + timer.listen(Event::Update); + timer.start(1.millis()).unwrap(); // Move the timer into our global storage *GINT.borrow(cs).borrow_mut() = Some(timer); diff --git a/examples/spi_hal_apa102c.rs b/examples/spi_hal_apa102c.rs index ba98d1c..000dd98 100644 --- a/examples/spi_hal_apa102c.rs +++ b/examples/spi_hal_apa102c.rs @@ -37,7 +37,7 @@ fn main() -> ! { let mut spi = p.SPI1.spi( (Some(sck), Some(miso), Some(mosi)), MODE, - 100_000.hz(), + 100_000.Hz(), &rcc.clocks, ); diff --git a/examples/spi_rc522.rs b/examples/spi_rc522.rs index cf07963..77b01e2 100644 --- a/examples/spi_rc522.rs +++ b/examples/spi_rc522.rs @@ -7,17 +7,13 @@ use panic_probe as _; use py32f0xx_hal as hal; use crate::hal::{ - delay::Delay, pac, prelude::*, spi::{Mode, Phase, Polarity}, - time::Hertz, - timers::Timer, }; use cortex_m_rt::entry; use defmt::{error, info}; use embedded_hal_02::blocking::delay::DelayMs; -use embedded_hal_02::timer::CountDown; use mfrc522::comm::eh02::spi::SpiInterface; use mfrc522::Mfrc522; @@ -42,7 +38,7 @@ fn main() -> ! { let mut flash = p.FLASH; let rcc = p.RCC.configure().freeze(&mut flash); - let mut delay = Delay::new(cp.SYST, &rcc); + let mut delay = cp.SYST.delay(&rcc.clocks); let gpioa = p.GPIOA.split(); @@ -61,7 +57,7 @@ fn main() -> ! { let spi = p.SPI1.spi( (Some(sck), Some(miso), Some(mosi)), MODE, - 1.mhz().into(), + 1.MHz().into(), &rcc.clocks, ); let itf = SpiInterface::new(spi).with_nss(nss).with_delay(|| { @@ -75,7 +71,8 @@ fn main() -> ! { info!("MFRC522 version: 0x{:02x}", ver); assert!(ver == 0x91 || ver == 0x92); - let mut timer = Timer::tim1(p.TIM1, Hertz(1), &rcc.clocks); + let mut timer = p.TIM1.counter_hz(&rcc.clocks); + timer.start(1.Hz()).unwrap(); loop { info!("Waiting for card..."); diff --git a/examples/watchdog.rs b/examples/watchdog.rs index c5e85be..6b13c99 100644 --- a/examples/watchdog.rs +++ b/examples/watchdog.rs @@ -5,7 +5,7 @@ use panic_halt as _; use py32f0xx_hal as hal; -use crate::hal::{delay::Delay, pac, prelude::*, time::Hertz, watchdog}; +use crate::hal::{pac, prelude::*, watchdog}; use core::fmt::Write; use cortex_m::peripheral::Peripherals; use cortex_m_rt::entry; @@ -16,7 +16,7 @@ use embedded_hal_02::watchdog::{Watchdog, WatchdogEnable}; fn main() -> ! { if let (Some(p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { let mut flash = p.FLASH; - let mut rcc = p.RCC.configure().sysclk(8.mhz()).freeze(&mut flash); + let mut rcc = p.RCC.configure().sysclk(8.MHz()).freeze(&mut flash); let gpioa = p.GPIOA.split(); let dbg = p.DBG; @@ -27,7 +27,7 @@ fn main() -> ! { let mut watchdog = watchdog::Watchdog::new(&mut rcc, p.IWDG); // Get delay provider - let mut delay = Delay::new(cp.SYST, &rcc); + let mut delay = cp.SYST.delay(&rcc.clocks); // Configure serial TX pin let tx = gpioa.pa2.into_alternate_af1(); @@ -37,7 +37,7 @@ fn main() -> ! { serial.write_str("RESET \r\n").ok(); - watchdog.start(Hertz(1)); + watchdog.start(1.Hz()); delay.delay_ms(500_u16); watchdog.feed(); serial.write_str("Feed the dog 1st\r\n").ok(); diff --git a/src/adc.rs b/src/adc.rs index 711c059..db1c64e 100644 --- a/src/adc.rs +++ b/src/adc.rs @@ -45,13 +45,10 @@ const VTEMPVAL_DELTA: u16 = VTEMPVAL_HIGH - VTEMPVAL_LOW; use core::ptr; -use embedded_hal_02::{ - adc::{Channel, OneShot}, - blocking::delay::DelayUs, -}; +use embedded_hal_02::adc::{Channel, OneShot}; +use embedded_hal_02::blocking::delay::DelayUs; use crate::{ - delay::Delay, gpio::*, pac::{ adc::{ @@ -72,9 +69,9 @@ pub struct Adc { precision: AdcPrecision, } -#[derive(Clone, Copy, Debug, PartialEq)] /// ADC Clock mode, select adc clock source /// +#[derive(Clone, Copy, Debug, PartialEq)] pub enum AdcClockMode { /// PCLK Pclk, @@ -134,10 +131,10 @@ impl From for CKMODE_A { } } -#[derive(Clone, Copy, Debug, PartialEq)] /// ADC Sampling time /// /// Options for the sampling time, each is T + 0.5 ADC clock cycles. +#[derive(Copy, Clone, Debug, PartialEq)] pub enum AdcSampleTime { /// 3.5 cycles sampling time T_3, @@ -179,8 +176,8 @@ impl From for SMP_A { } } -#[derive(Clone, Copy, Debug, PartialEq)] /// ADC Result Alignment +#[derive(Copy, Clone, Debug, PartialEq)] pub enum AdcAlign { /// Left aligned results (most significant bits) /// @@ -219,8 +216,8 @@ impl From for ALIGN_A { } } -#[derive(Clone, Copy, Debug, PartialEq)] /// ADC Sampling Precision +#[derive(Copy, Clone, Debug, PartialEq)] pub enum AdcPrecision { /// 12 bit precision B_12, @@ -327,7 +324,7 @@ impl VTemp { /// Given a delay reference it will attempt to restrict to the /// minimum delay needed to ensure a 10 us tSTART value. /// Otherwise it will approximate the required delay using ADC reads. - pub fn read(adc: &mut Adc, delay: Option<&mut Delay>) -> i16 { + pub fn read(adc: &mut Adc, delay: Option<&mut dyn DelayUs>) -> i16 { let mut vtemp = Self::new(); let vtemp_preenable = vtemp.is_enabled(adc); @@ -335,7 +332,7 @@ impl VTemp { vtemp.enable(adc); if let Some(dref) = delay { - dref.delay_us(2_u16); + dref.delay_us(2); } else { // Double read of vdda to allow sufficient startup time for the temp sensor VRef::read_vdda(adc); diff --git a/src/delay.rs b/src/delay.rs deleted file mode 100644 index 9cc27dc..0000000 --- a/src/delay.rs +++ /dev/null @@ -1,125 +0,0 @@ -//! API for delays with the systick timer -//! -//! Please be aware of potential overflows when using `delay_us`. -//! E.g. at 48MHz the maximum delay is 89 seconds. -//! -//! Consider using the timers api as a more flexible interface -//! -//! # Example -//! -//! ``` no_run -//! use py32f0xx_hal as hal; -//! -//! use crate::hal::pac; -//! use crate::hal::prelude::*; -//! use crate::hal::delay::Delay; -//! use cortex_m::peripheral::Peripherals; -//! -//! let mut p = pac::Peripherals::take().unwrap(); -//! let mut cp = cortex_m::Peripherals::take().unwrap(); -//! -//! let mut rcc = p.RCC.configure().freeze(&mut p.FLASH); -//! let mut delay = Delay::new(cp.SYST, &rcc); -//! loop { -//! delay.delay_ms(1_000_u16); -//! } -//! ``` - -use cast::{u16, u32}; -use cortex_m::peripheral::syst::SystClkSource; -use cortex_m::peripheral::SYST; - -use crate::rcc::Rcc; - -use embedded_hal_02::blocking::delay::{DelayMs, DelayUs}; - -/// System timer (SysTick) as a delay provider -#[derive(Clone)] -pub struct Delay { - scale: u32, -} - -const SYSTICK_RANGE: u32 = 0x0100_0000; - -impl Delay { - /// Configures the system timer (SysTick) as a delay provider - pub fn new(mut syst: SYST, rcc: &Rcc) -> Delay { - syst.set_clock_source(SystClkSource::Core); - - syst.set_reload(SYSTICK_RANGE - 1); - syst.clear_current(); - syst.enable_counter(); - - assert!(rcc.clocks.hclk().0 >= 1_000_000); - let scale = rcc.clocks.hclk().0 / 1_000_000; - - Delay { scale } - // As access to the count register is possible without a reference to the systick, we can - // just drop it - } -} - -impl DelayMs for Delay { - // At 48 MHz (the maximum frequency), calling delay_us with ms * 1_000 directly overflows at 0x15D86 (just over the max u16 value) - // So we implement a separate, higher level, delay loop - fn delay_ms(&mut self, mut ms: u32) { - const MAX_MS: u32 = 0x0000_FFFF; - while ms != 0 { - let current_ms = if ms <= MAX_MS { ms } else { MAX_MS }; - self.delay_us(current_ms * 1_000); - ms -= current_ms; - } - } -} - -impl DelayMs for Delay { - fn delay_ms(&mut self, ms: u16) { - // Call delay_us directly, so we don't have to use the additional - // delay loop the u32 variant uses - self.delay_us(u32(ms) * 1_000); - } -} - -impl DelayMs for Delay { - fn delay_ms(&mut self, ms: u8) { - self.delay_ms(u16(ms)); - } -} - -// At 48MHz (the maximum frequency), this overflows at approx. 2^32 / 48 = 89 seconds -impl DelayUs for Delay { - fn delay_us(&mut self, us: u32) { - // The SysTick Reload Value register supports values between 1 and 0x00FFFFFF. - // Here less than maximum is used so we have some play if there's a long running interrupt. - const MAX_TICKS: u32 = 0x007F_FFFF; - - let mut total_ticks = us * self.scale; - - while total_ticks != 0 { - let current_ticks = if total_ticks <= MAX_TICKS { - total_ticks - } else { - MAX_TICKS - }; - - let start_count = SYST::get_current(); - total_ticks -= current_ticks; - - // Use the wrapping substraction and the modulo to deal with the systick wrapping around - // from 0 to 0xFFFF - while (start_count.wrapping_sub(SYST::get_current()) % SYSTICK_RANGE) < current_ticks {} - } - } -} - -impl DelayUs for Delay { - fn delay_us(&mut self, us: u16) { - self.delay_us(u32(us)) - } -} - -impl DelayUs for Delay { - fn delay_us(&mut self, us: u8) { - self.delay_us(u32(us)) - } -} diff --git a/src/dma.rs b/src/dma.rs index 5f7a98b..e3a9c84 100644 --- a/src/dma.rs +++ b/src/dma.rs @@ -12,6 +12,7 @@ use embedded_dma::{ReadBuffer, WriteBuffer}; #[derive(Debug)] #[non_exhaustive] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] pub enum Error { Overrun, } diff --git a/src/gpio.rs b/src/gpio.rs index c27b2df..f74b677 100644 --- a/src/gpio.rs +++ b/src/gpio.rs @@ -80,7 +80,7 @@ pub trait PinExt { /// Return port id /// - /// id is a character, such as 'A' for porta, 'B' for portb + /// id is ascii byte, 'A' for porta, 'B' for portb fn port_id(&self) -> u8; } @@ -253,21 +253,26 @@ where fn make_interrupt_source(&mut self, exti: &mut pac::EXTI) { let pin_number = self.pin_id(); let offset = 8 * (pin_number % 4); + // for pins 0-3, mux selects ports a=0, b=1, or f=2 + // for py32f002b, a=0, b=1, c=2 let port = match self.port_id() { b'A' => 0, b'B' => 1, b'C' | b'F' => 2, _ => unreachable!(), }; + // note(Safety) While the match below has invalid combinations for some parts, it cannot + // actually hit those, because the match works off the pin and port number which is embedded + // in the pin as states, so they can't have an invalid combination + // For example there only 2 pins on port C of the py32f002b match pin_number { - // for pins 0-3, mux selects ports a=0, b=1, or f=2 - // for py32f002b, a=0, b=1, c=2 + // pins 0-3, mux selects port as above 0..=3 => { exti.exticr1.modify(|r, w| unsafe { w.bits((r.bits() & !(0xf << offset)) | (port << offset)) }); } - // pin 4 is same as pins 0-3 + // pin 4 mux selects port 4 => { exti.exticr2.modify(|r, w| unsafe { w.bits((r.bits() & !(0xf << offset)) | (port << offset)) @@ -278,13 +283,13 @@ where exti.exticr2 .modify(|r, w| unsafe { w.bits(r.bits() | (port << offset)) }); } - // BUGBUG: py32f002a only has 8 pins? pin 8, mux selects ports a=0, b=1 + // BUGBUG: py32f002a only has 15 port A pins? pin 8, mux selects ports a=0, b=1 #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] 8 => { exti.exticr3 .modify(|r, w| unsafe { w.bits(r.bits() | (port << offset)) }); } - // BUGBUG: py32f002a only has 8 pins? pin 9-15, no mux + // BUGBUG: py32f002a only has 15 port A pins? pin 9-15, no mux #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] 9..=15 => {} _ => unreachable!(), @@ -358,6 +363,7 @@ impl Active for Dynamic {} /// `Dynamic` pin error #[derive(Debug, PartialEq, Eq)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] pub enum PinModeError { IncorrectMode, } @@ -1151,6 +1157,7 @@ impl Alternate { } } +#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] gpio!(GPIOA, gpioa, PAx, 'A', [ PA0: (pa0, 0), PA1: (pa1, 1), @@ -1170,6 +1177,19 @@ gpio!(GPIOA, gpioa, PAx, 'A', [ PA15: (pa15, 15), ]); +#[cfg(feature = "py32f002b")] +gpio!(GPIOA, gpioa, PAx, 'A', [ + PA0: (pa0, 0), + PA1: (pa1, 1), + PA2: (pa2, 2, Debugger), + PA3: (pa3, 3), + PA4: (pa4, 4), + PA5: (pa5, 5), + PA6: (pa6, 6), + PA7: (pa7, 7), +]); + +#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] gpio!(GPIOB, gpiob, PBx, 'B', [ PB0: (pb0, 0), PB1: (pb1, 1), @@ -1182,6 +1202,19 @@ gpio!(GPIOB, gpiob, PBx, 'B', [ PB8: (pb8, 8), ]); +#[cfg(feature = "py32f002b")] +gpio!(GPIOB, gpiob, PBx, 'B', [ + PB0: (pb0, 0), + PB1: (pb1, 1), + PB2: (pb2, 2), + PB3: (pb3, 3), + PB4: (pb4, 4), + PB5: (pb5, 5), + PB6: (pb6, 6, Debugger), + PB7: (pb7, 7), + PB8: (pb8, 8), +]); + #[cfg(feature = "py32f002b")] gpio!(GPIOC, gpioc, PCx, 'C', [ PC0: (pc0, 0), diff --git a/src/i2c.rs b/src/i2c.rs index 2245d7d..3e59eef 100644 --- a/src/i2c.rs +++ b/src/i2c.rs @@ -6,7 +6,7 @@ use crate::{ gpio::*, pac, rcc::{Clocks, Enable, Reset}, - time::{Hertz, KiloHertz, U32Ext}, + time::{kHz, Hertz, KiloHertz}, }; /// I2C abstraction @@ -76,6 +76,7 @@ i2c_pins! { } #[derive(Debug)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] pub enum Error { OVERRUN, NACK, @@ -133,24 +134,24 @@ where // Make sure the I2C unit is disabled so we can configure it self.i2c.cr1.modify(|_, w| w.pe().clear_bit()); - let f = freq.0 / 1_000_000; + let f = freq.raw() / 1_000_000; self.i2c .cr2 .write(|w| unsafe { w.freq().bits(f.clamp(4, 48) as u8) }); // Normal I2C speeds use a different scaling than fast mode below - let (f_s, ccr) = if speed <= 100_u32.khz() { + let (f_s, ccr) = if speed <= kHz(100) { // This is a normal I2C mode - (false, freq.0 / (speed.0 * 2)) + (false, freq.raw() / (speed.raw() * 2)) } else { // This is a fast I2C mode ( true, if self.i2c.ccr.read().duty().bit_is_set() { - freq.0 / (speed.0 * 25) + freq.raw() / (speed.raw() * 25) } else { - freq.0 / (speed.0 * 3) + freq.raw() / (speed.raw() * 3) }, ) }; diff --git a/src/lib.rs b/src/lib.rs index 008e5fd..24eccce 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -15,8 +15,6 @@ pub use py32f0::py32f030 as pac; #[cfg(feature = "device-selected")] pub mod adc; -#[cfg(feature = "device-selected")] -pub mod delay; #[cfg(all(feature = "device-selected", feature = "with-dma"))] pub mod dma; #[cfg(feature = "device-selected")] @@ -38,7 +36,7 @@ pub mod spi; #[cfg(feature = "device-selected")] pub mod time; #[cfg(feature = "device-selected")] -pub mod timers; +pub mod timer; #[cfg(feature = "device-selected")] pub mod watchdog; diff --git a/src/prelude.rs b/src/prelude.rs index 428089c..9e6a75e 100644 --- a/src/prelude.rs +++ b/src/prelude.rs @@ -13,3 +13,7 @@ pub use crate::rcc::RccExt as _py32f0xx_hal_rcc_RccExt; pub use crate::serial::SerialExt as _py32f0xx_hal_serial_SerialExt; pub use crate::spi::SpiExt as _py32f0xx_hal_spi_SpiExt; pub use crate::time::U32Ext as _py32f0xx_hal_time_U32Ext; +pub use crate::timer::SysTimerExt as _py32f0xx_hal_timer_SysTimerExt; +pub use crate::timer::TimerExt as _py32f0xx_hal_timer_TimerExt; +pub use fugit::ExtU32 as _fugit_ExtU32; +pub use fugit::RateExtU32 as _fugit_RateExtU32; diff --git a/src/pwm.rs b/src/pwm.rs index e84e2ed..728fe41 100644 --- a/src/pwm.rs +++ b/src/pwm.rs @@ -16,13 +16,13 @@ pub trait Pins { const C4: bool = false; type Channels; } -use crate::timers::PinC1; -use crate::timers::PinC1N; -use crate::timers::PinC2; -use crate::timers::PinC2N; -use crate::timers::PinC3; -use crate::timers::PinC3N; -use crate::timers::PinC4; +use crate::timer::PinC1; +use crate::timer::PinC1N; +use crate::timer::PinC2; +use crate::timer::PinC2N; +use crate::timer::PinC3; +use crate::timer::PinC3N; +use crate::timer::PinC4; pub struct C1; pub struct C1N; @@ -154,7 +154,7 @@ macro_rules! pwm_4_channels { .modify(|_, w| w.oc4pe().set_bit().oc4m().pwm_mode1() ); } - let ticks = $TIMX::timer_clock(clocks).0 / freq.into().0; + let ticks = $TIMX::timer_clock(clocks).raw() / freq.into().raw(); let psc = u16((ticks - 1) / (1 << 16)).unwrap(); tim.psc.write(|w| unsafe { w.psc().bits(psc) }); @@ -337,7 +337,7 @@ macro_rules! pwm_4_channels_with_3_complementary_outputs { .modify(|_, w| w.oc4pe().set_bit().oc4m().pwm_mode1() ); } - let ticks = $TIMX::timer_clock(clocks).0 / freq.into().0; + let ticks = $TIMX::timer_clock(clocks).raw() / freq.into().raw(); let psc = u16((ticks - 1) / (1 << 16)).unwrap(); tim.psc.write(|w| unsafe { w.psc().bits(psc) }); @@ -701,7 +701,7 @@ macro_rules! pwm_1_channel { tim.ccmr1_output().modify(|_, w| w.oc1pe().set_bit().oc1m().bits(6)); } - let ticks = $TIMX::timer_clock(clocks).0 / freq.into().0; + let ticks = $TIMX::timer_clock(clocks).raw() / freq.into().raw(); let psc = u16((ticks - 1) / (1 << 16)).unwrap(); tim.psc.write(|w| unsafe { w.psc().bits(psc) }); @@ -776,7 +776,7 @@ macro_rules! pwm_1_channel_with_complementary_outputs { tim.ccmr1_output().modify(|_, w| w.oc1pe().set_bit().oc1m().bits(6)); } - let ticks = $TIMX::timer_clock(clocks).0 / freq.into().0; + let ticks = $TIMX::timer_clock(clocks).raw() / freq.into().raw(); let psc = u16((ticks - 1) / (1 << 16)).unwrap(); tim.psc.write(|w| unsafe { w.psc().bits(psc) }); diff --git a/src/rcc.rs b/src/rcc.rs index a10dd5e..9c75f80 100644 --- a/src/rcc.rs +++ b/src/rcc.rs @@ -6,7 +6,7 @@ use crate::pac::rcc::{ }; use crate::pac::{DBG, PWR, RCC}; -use crate::time::Hertz; +use crate::time::{Hertz, Hz}; mod enable; @@ -35,11 +35,25 @@ pub struct Rcc { } impl Rcc { + /// Configure the Main Clock Output + /// set the MCO pin output source and prescalar pub fn configure_mco(&self, sel: MCOSrc, pre: MCODiv) { self.regs .cfgr .modify(|_, w| w.mcopre().variant(pre.into()).mcosel().variant(sel.into())); } + /// Set the clock debug stop mode + /// false - fclk and hclk are disabled in stop mode (Identical to after reset) + /// true - fclk and hclk are not disabled in stop mode and set by hsi + pub fn debug_stop_mode(&mut self, dbg: DBG, set: bool) { + dbg.cr.write(|w| { + if set { + w.dbg_stop().enabled() + } else { + w.dbg_stop().disabled() + } + }); + } } /// AMBA High-performance Bus (AHB) registers @@ -78,7 +92,6 @@ pub enum MCOSrc { Pll = 5, ///6: LSI oscillator clock selected Lsi = 6, - #[cfg(feature = "py32f030")] ///7: LSE oscillator clock selected Lse = 7, @@ -185,14 +198,15 @@ impl From for HSI_FS_A { } } +#[derive(Clone, Copy)] pub enum HSEBypassMode { /// Not bypassed: for crystals NotBypassed, /// Bypassed: for external clock sources Bypassed, } + /// RCC for F0x0 devices -//#[cfg(any(feature = "py32f030", feature = "py32f003"))] mod inner { use crate::pac::{rcc::cfgr::SW_A, RCC}; @@ -421,7 +435,7 @@ impl Clocks { /// Returns the frequency of the APB Timers /// If pclk is prescaled from hclk, the frequency fed into the timers is doubled pub const fn pclk_tim(&self) -> Hertz { - Hertz(self.pclk.0 * if self.ppre() == 1 { 1 } else { 2 }) + Hertz::from_raw(self.pclk.raw() * if self.ppre() == 1 { 1 } else { 2 }) } pub(crate) const fn ppre(&self) -> u8 { @@ -445,7 +459,7 @@ impl CFGR { where F: Into, { - self.clock_src = SysClkSource::HSE(freq.into().0, bypass); + self.clock_src = SysClkSource::HSE(freq.into().raw(), bypass); self } #[cfg(feature = "py32f002b")] @@ -453,7 +467,7 @@ impl CFGR { where F: Into, { - self.clock_src = SysClkSource::HSE(freq.into().0, HSEBypassMode::Bypassed); + self.clock_src = SysClkSource::HSE(freq.into().raw(), HSEBypassMode::Bypassed); self } @@ -466,7 +480,7 @@ impl CFGR { where F: Into, { - self.hclk = Some(freq.into().0); + self.hclk = Some(freq.into().raw()); self } @@ -474,7 +488,7 @@ impl CFGR { where F: Into, { - self.pclk = Some(freq.into().0); + self.pclk = Some(freq.into().raw()); self } @@ -482,7 +496,7 @@ impl CFGR { where F: Into, { - self.sysclk = Some(freq.into().0); + self.sysclk = Some(freq.into().raw()); self } @@ -588,9 +602,9 @@ impl CFGR { } Rcc { clocks: Clocks { - hclk: Hertz(hclk), - pclk: Hertz(pclk), - sysclk: Hertz(sysclk), + hclk: Hz(hclk), + pclk: Hz(pclk), + sysclk: Hz(sysclk), ppre, }, regs: self.rcc, diff --git a/src/rcc/enable.rs b/src/rcc/enable.rs index f9306b7..249a33a 100644 --- a/src/rcc/enable.rs +++ b/src/rcc/enable.rs @@ -80,6 +80,7 @@ bus! { #[cfg(any(feature = "py32f003", feature = "py32f030"))] bus! { TIM3 => (APB, apbenr1, apbrstr1, 1), + TIM17 => (APB, apbenr2, apbrstr2, 18), } #[cfg(any(feature = "py32f002b", feature = "py32f003", feature = "py32f030"))] @@ -91,8 +92,3 @@ bus! { bus! { TIM16 => (APB, apbenr2, apbrstr2, 17), } - -#[cfg(any(feature = "py32f003", feature = "py32f030"))] -bus! { - TIM17 => (APB, apbenr2, apbrstr2, 18), -} diff --git a/src/rtc.rs b/src/rtc.rs index c3e5ec6..8d3803a 100644 --- a/src/rtc.rs +++ b/src/rtc.rs @@ -3,14 +3,14 @@ */ use crate::pac::{RCC, RTC}; -use crate::time::Hertz; +use crate::time::{Hertz, Hz}; use core::convert::Infallible; use core::marker::PhantomData; // The LSE runs at at 32 768 hertz unless an external clock is provided -const LSE_HERTZ: Hertz = Hertz(32_768); -const LSI_HERTZ: Hertz = Hertz(32_768); +const LSE_HERTZ: Hertz = Hz(32_768); +const LSI_HERTZ: Hertz = Hz(32_768); /// RTC clock source HSE clock divided by 128 (type state) pub struct RtcClkHseDiv128; @@ -66,7 +66,7 @@ impl Rtc { Self::enable_rtc(); // Set the prescaler to make it count up once every second. - let prl = LSE_HERTZ.0 - 1; + let prl = LSE_HERTZ.raw() - 1; assert!(prl < 1 << 20); result.perform_write(|s| { s.regs.prlh.write(|w| unsafe { w.bits(prl >> 16) }); @@ -144,7 +144,7 @@ impl Rtc { Self::enable_rtc(); // Set the prescaler to make it count up once every second. - let prl = LSI_HERTZ.0 - 1; + let prl = LSI_HERTZ.raw() - 1; assert!(prl < 1 << 20); result.perform_write(|s| { s.regs.prlh.write(|w| unsafe { w.bits(prl >> 16) }); @@ -212,7 +212,7 @@ impl Rtc { Self::enable_rtc(); // Set the prescaler to make it count up once every second. - let prl = hse.0 / 128 - 1; + let prl = hse.raw() / 128 - 1; assert!(prl < 1 << 20); result.perform_write(|s| { s.regs.prlh.write(|w| unsafe { w.bits(prl >> 16) }); @@ -264,9 +264,9 @@ impl Rtc { pub fn select_frequency(&mut self, frequency: Hertz) { // The manual says that the zero value for the prescaler is not recommended, thus the // minimum division factor is 2 (prescaler + 1) - assert!(frequency.0 <= LSE_HERTZ.0 / 2); + assert!(frequency <= LSE_HERTZ / 2); - let prescaler = LSE_HERTZ.0 / frequency.0 - 1; + let prescaler = LSE_HERTZ.raw() / frequency.raw() - 1; self.perform_write(|s| { s.regs.prlh.write(|w| unsafe { w.bits(prescaler >> 16) }); s.regs diff --git a/src/serial.rs b/src/serial.rs index caaae9b..ea588d8 100644 --- a/src/serial.rs +++ b/src/serial.rs @@ -254,6 +254,7 @@ inst! { /// Serial error #[derive(Debug)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] #[non_exhaustive] pub enum Error { /// The peripheral receive buffer was overrun. @@ -519,7 +520,7 @@ fn apply_config(config: Config, clocks: &Clocks) { let usart = unsafe { &*USART::ptr() }; // Configure baud rate - let brr = USART::clock(clocks).0 / config.baudrate.0; + let brr = USART::clock(clocks).raw() / config.baudrate.0; assert!(brr >= 16, "impossible baud rate"); usart.brr.write(|w| unsafe { w.bits(brr) }); diff --git a/src/spi.rs b/src/spi.rs index 4cf3670..c186d05 100644 --- a/src/spi.rs +++ b/src/spi.rs @@ -110,6 +110,7 @@ pub enum SpiBitFormat { /// SPI error #[non_exhaustive] #[derive(Debug)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] pub enum Error { /// Overrun occurred Overrun, @@ -408,7 +409,7 @@ impl /* Make sure the SPI unit is disabled so we can configure it */ spi.cr1.modify(|_, w| w.spe().clear_bit()); - let br = match clocks.pclk().0 / speed.into().0 { + let br = match clocks.pclk().raw() / speed.into().raw() { 0 => unreachable!(), 1..=2 => 0b000, 3..=5 => 0b001, diff --git a/src/time.rs b/src/time.rs index d870961..f2637ab 100644 --- a/src/time.rs +++ b/src/time.rs @@ -1,63 +1,114 @@ -/// Bits per second -#[derive(PartialEq, PartialOrd, Clone, Copy)] -pub struct Bps(pub u32); +//! Time units +//! +//! See [`Hertz`], [`KiloHertz`] and [`MegaHertz`] for creating increasingly higher frequencies. +//! +//! The [`fugit::ExtU32`] [`U32Ext`] trait adds various methods like `.Hz()`, `.MHz()`, etc to the `u32` primitive type, +//! allowing it to be converted into frequencies. +//! +//! # Examples +//! +//! ## Create a 2 MHz frequency +//! +//! This example demonstrates various ways of creating a 2 MHz (2_000_000 Hz) frequency. They are +//! all equivalent, however the `2.MHz()` variant should be preferred for readability. +//! +//! ```rust +//! use stm32f1xx_hal::{ +//! time::Hertz, +//! // Imports U32Ext trait +//! prelude::*, +//! }; +//! +//! let freq_hz = 2_000_000.Hz(); +//! let freq_khz = 2_000.kHz(); +//! let freq_mhz = 2.MHz(); +//! +//! assert_eq!(freq_hz, freq_khz); +//! assert_eq!(freq_khz, freq_mhz); +//! ``` + +#![allow(non_snake_case)] -#[derive(PartialEq, PartialOrd, Clone, Copy)] -pub struct Hertz(pub u32); +use core::ops; -#[derive(PartialEq, PartialOrd, Clone, Copy)] -pub struct KiloHertz(pub u32); +/// Bits per second +#[derive(Clone, Copy, PartialEq, Eq, PartialOrd, Debug)] +pub struct Bps(pub u32); -#[derive(PartialEq, PartialOrd, Clone, Copy)] -pub struct MegaHertz(pub u32); +pub use fugit::{ + HertzU32 as Hertz, KilohertzU32 as KiloHertz, MegahertzU32 as MegaHertz, + MicrosDurationU32 as MicroSeconds, MillisDurationU32 as MilliSeconds, +}; /// Extension trait that adds convenience methods to the `u32` type pub trait U32Ext { /// Wrap in `Bps` fn bps(self) -> Bps; - - /// Wrap in `Hertz` - fn hz(self) -> Hertz; - - /// Wrap in `KiloHertz` - fn khz(self) -> KiloHertz; - - /// Wrap in `MegaHertz` - fn mhz(self) -> MegaHertz; } impl U32Ext for u32 { fn bps(self) -> Bps { Bps(self) } +} - fn hz(self) -> Hertz { - Hertz(self) - } +pub const fn Hz(val: u32) -> Hertz { + Hertz::from_raw(val) +} - fn khz(self) -> KiloHertz { - KiloHertz(self) - } +pub const fn kHz(val: u32) -> KiloHertz { + KiloHertz::from_raw(val) +} - fn mhz(self) -> MegaHertz { - MegaHertz(self) - } +pub const fn MHz(val: u32) -> MegaHertz { + MegaHertz::from_raw(val) } -impl From for Hertz { - fn from(khz: KiloHertz) -> Self { - Hertz(khz.0 * 1_000) - } +pub const fn ms(val: u32) -> MilliSeconds { + MilliSeconds::from_ticks(val) } -impl From for Hertz { - fn from(mhz: MegaHertz) -> Self { - Hertz(mhz.0 * 1_000_000) - } +pub const fn us(val: u32) -> MicroSeconds { + MicroSeconds::from_ticks(val) } -impl From for KiloHertz { - fn from(mhz: MegaHertz) -> Self { - KiloHertz(mhz.0 * 1_000) - } +/// Macro to implement arithmetic operations (e.g. multiplication, division) +/// for wrapper types. +macro_rules! impl_arithmetic { + ($wrapper:ty, $wrapped:ty) => { + impl ops::Mul<$wrapped> for $wrapper { + type Output = Self; + fn mul(self, rhs: $wrapped) -> Self { + Self(self.0 * rhs) + } + } + + impl ops::MulAssign<$wrapped> for $wrapper { + fn mul_assign(&mut self, rhs: $wrapped) { + self.0 *= rhs; + } + } + + impl ops::Div<$wrapped> for $wrapper { + type Output = Self; + fn div(self, rhs: $wrapped) -> Self { + Self(self.0 / rhs) + } + } + + impl ops::Div<$wrapper> for $wrapper { + type Output = $wrapped; + fn div(self, rhs: $wrapper) -> $wrapped { + self.0 / rhs.0 + } + } + + impl ops::DivAssign<$wrapped> for $wrapper { + fn div_assign(&mut self, rhs: $wrapped) { + self.0 /= rhs; + } + } + }; } + +impl_arithmetic!(Bps, u32); diff --git a/src/timer.rs b/src/timer.rs new file mode 100644 index 0000000..8c22e99 --- /dev/null +++ b/src/timer.rs @@ -0,0 +1,565 @@ +//! API for the integrated timers +//! +//! This only implements basic functions, a lot of things are missing +//! +//! # Example +//! Blink the led with 1Hz +//! ``` no_run +//! use py32f0xx_hal as hal; +//! +//! use crate::hal::pac; +//! use crate::hal::prelude::*; +//! use crate::hal::timer::*; +//! use nb::block; +//! +//! let mut p = pac::Peripherals::take().unwrap(); +//! let rcc = p.RCC.configure().freeze(&mut p.FLASH); +//! +//! let gpioa = p.GPIOA.split(); +//! +//! let mut led = gpioa.pa1.into_push_pull_pull_output(); +//! +//! let mut timer = p.TIM1.counter_hz(&rcc.clocks); +//! timer.start(1.Hz()).unwrap(); +//! loop { +//! led.toggle(); +//! block!(timer.wait()).ok(); +//! } +//! ``` + +#![allow(non_upper_case_globals)] + +use crate::pac::{self, DBG}; +use crate::rcc::{BusTimerClock, Clocks, Enable, Reset}; +use crate::time::{Hertz, Hz}; +use core::convert::TryFrom; +use cortex_m::peripheral::syst::SystClkSource; +use cortex_m::peripheral::SYST; + +#[cfg(feature = "rtic")] +pub mod monotonic; +#[cfg(feature = "rtic")] +pub use monotonic::*; +pub(crate) mod pins; +pub use pins::*; +pub mod delay; +pub use delay::*; +pub mod counter; +pub use counter::*; + +mod hal_02; +mod hal_1; + +/// Hardware timers +pub struct Timer { + clk: Hertz, + tim: TIM, +} + +/// Interrupt events +pub enum SysEvent { + /// Timer timed out / count down ended + Update, +} + +bitflags::bitflags! { + pub struct Event: u32 { + const Update = 1 << 0; + const C1 = 1 << 1; + const C2 = 1 << 2; + const C3 = 1 << 3; + const C4 = 1 << 4; + } +} + +#[derive(Debug, Eq, PartialEq, Copy, Clone)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +pub enum Error { + /// Timer is disabled + Disabled, + WrongAutoReload, +} + +pub trait TimerExt: Sized { + /// Non-blocking [Counter] with custom fixed precision + fn counter(self, clocks: &Clocks) -> Counter; + /// Non-blocking [Counter] with fixed precision of 1 ms (1 kHz sampling) + /// + /// Can wait from 2 ms to 65 sec for 16-bit timer and from 2 ms to 49 days for 32-bit timer. + /// + /// NOTE: don't use this if your system frequency more than 65 MHz + fn counter_ms(self, clocks: &Clocks) -> CounterMs { + self.counter::<1_000>(clocks) + } + /// Non-blocking [Counter] with fixed precision of 1 μs (1 MHz sampling) + /// + /// Can wait from 2 μs to 65 ms for 16-bit timer and from 2 μs to 71 min for 32-bit timer. + fn counter_us(self, clocks: &Clocks) -> CounterUs { + self.counter::<1_000_000>(clocks) + } + /// Non-blocking [Counter] with dynamic precision which uses `Hertz` as Duration units + fn counter_hz(self, clocks: &Clocks) -> CounterHz; + + /// Blocking [Delay] with custom fixed precision + fn delay(self, clocks: &Clocks) -> Delay; + /// Blocking [Delay] with fixed precision of 1 ms (1 kHz sampling) + /// + /// Can wait from 2 ms to 49 days. + /// + /// NOTE: don't use this if your system frequency more than 65 MHz + fn delay_ms(self, clocks: &Clocks) -> DelayMs { + self.delay::<1_000>(clocks) + } + /// Blocking [Delay] with fixed precision of 1 μs (1 MHz sampling) + /// + /// Can wait from 2 μs to 71 min. + fn delay_us(self, clocks: &Clocks) -> DelayUs { + self.delay::<1_000_000>(clocks) + } +} + +impl TimerExt for TIM { + fn counter(self, clocks: &Clocks) -> Counter { + FTimer::new(self, clocks).counter() + } + fn counter_hz(self, clocks: &Clocks) -> CounterHz { + Timer::new(self, clocks).counter_hz() + } + fn delay(self, clocks: &Clocks) -> Delay { + FTimer::new(self, clocks).delay() + } +} + +pub trait SysTimerExt: Sized { + /// Creates timer which takes [Hertz] as Duration + fn counter_hz(self, clocks: &Clocks) -> SysCounterHz; + + /// Creates timer with custom precision (core frequency recommended is known) + fn counter(self, clocks: &Clocks) -> SysCounter; + /// Creates timer with precision of 1 μs (1 MHz sampling) + fn counter_us(self, clocks: &Clocks) -> SysCounterUs { + self.counter::<1_000_000>(clocks) + } + /// Blocking [Delay] with custom precision + fn delay(self, clocks: &Clocks) -> SysDelay; +} + +impl SysTimerExt for SYST { + fn counter_hz(self, clocks: &Clocks) -> SysCounterHz { + Timer::syst(self, clocks).counter_hz() + } + fn counter(self, clocks: &Clocks) -> SysCounter { + Timer::syst(self, clocks).counter() + } + fn delay(self, clocks: &Clocks) -> SysDelay { + Timer::syst_external(self, clocks).delay() + } +} + +impl Timer { + /// Initialize SysTick timer + pub fn syst(mut tim: SYST, clocks: &Clocks) -> Self { + tim.set_clock_source(SystClkSource::Core); + Self { + tim, + clk: clocks.sysclk(), + } + } + + /// Initialize SysTick timer and set it frequency to `HCLK / 8` + pub fn syst_external(mut tim: SYST, clocks: &Clocks) -> Self { + tim.set_clock_source(SystClkSource::External); + Self { + tim, + clk: Hz(clocks.hclk().raw() / 8), + } + } + + pub fn configure(&mut self, clocks: &Clocks) { + self.tim.set_clock_source(SystClkSource::Core); + self.clk = clocks.hclk(); + } + + pub fn configure_external(&mut self, clocks: &Clocks) { + self.tim.set_clock_source(SystClkSource::External); + self.clk = Hz(clocks.hclk().raw() / 8); + } + + pub fn release(self) -> SYST { + self.tim + } + + /// Starts listening for an `event` + pub fn listen(&mut self, event: SysEvent) { + match event { + SysEvent::Update => self.tim.enable_interrupt(), + } + } + + /// Stops listening for an `event` + pub fn unlisten(&mut self, event: SysEvent) { + match event { + SysEvent::Update => self.tim.disable_interrupt(), + } + } + + /// Resets the counter + pub fn reset(&mut self) { + // According to the Cortex-M3 Generic User Guide, the interrupt request is only generated + // when the counter goes from 1 to 0, so writing zero should not trigger an interrupt + self.tim.clear_current(); + } +} + +mod sealed { + use super::{Event, DBG}; + pub trait General { + type Width: Into + From; + fn max_auto_reload() -> u32; + unsafe fn set_auto_reload_unchecked(&mut self, arr: u32); + fn set_auto_reload(&mut self, arr: u32) -> Result<(), super::Error>; + fn read_auto_reload() -> u32; + fn enable_preload(&mut self, b: bool); + fn enable_counter(&mut self); + fn disable_counter(&mut self); + fn is_counter_enabled(&self) -> bool; + fn reset_counter(&mut self); + fn set_prescaler(&mut self, psc: u16); + fn read_prescaler(&self) -> u16; + fn trigger_update(&mut self); + fn clear_interrupt_flag(&mut self, event: Event); + fn listen_interrupt(&mut self, event: Event, b: bool); + fn get_interrupt_flag(&self) -> Event; + fn read_count(&self) -> Self::Width; + fn cr1_reset(&mut self); + fn stop_in_debug(&mut self, dbg: &mut DBG, state: bool); + } + + pub trait MasterTimer: General { + type Mms; + fn master_mode(&mut self, mode: Self::Mms); + } + + pub trait OnePulseMode: General { + fn start_one_pulse(&mut self); + } +} + +pub(crate) use sealed::{General, MasterTimer, OnePulseMode}; + +pub trait Instance: crate::Sealed + Enable + Reset + BusTimerClock + General {} + +macro_rules! hal { + ($($TIM:ty: [ + $Timer:ident, + $bits:ty, + $dbg_timX_reg:ident, + $dbg_timX_stop:ident, + $(m: $timbase:ident,)? + $(opm: $opm:ident,)? + ],)+) => { + $( + impl Instance for $TIM { } + pub type $Timer = Timer<$TIM>; + + impl General for $TIM { + type Width = $bits; + + #[inline(always)] + fn max_auto_reload() -> u32 { + <$bits>::MAX as u32 + } + #[inline(always)] + unsafe fn set_auto_reload_unchecked(&mut self, arr: u32) { + self.arr.write(|w| w.bits(arr)) + } + #[inline(always)] + fn set_auto_reload(&mut self, arr: u32) -> Result<(), Error> { + // Note: Make it impossible to set the ARR value to 0, since this + // would cause an infinite loop. + if arr > 0 && arr <= Self::max_auto_reload() { + Ok(unsafe { self.set_auto_reload_unchecked(arr) }) + } else { + Err(Error::WrongAutoReload) + } + } + #[inline(always)] + fn read_auto_reload() -> u32 { + let tim = unsafe { &*<$TIM>::ptr() }; + tim.arr.read().bits() + } + #[inline(always)] + fn enable_preload(&mut self, b: bool) { + self.cr1.modify(|_, w| w.arpe().bit(b)); + } + #[inline(always)] + fn enable_counter(&mut self) { + self.cr1.modify(|_, w| w.cen().set_bit()); + } + #[inline(always)] + fn disable_counter(&mut self) { + self.cr1.modify(|_, w| w.cen().clear_bit()); + } + #[inline(always)] + fn is_counter_enabled(&self) -> bool { + self.cr1.read().cen().is_enabled() + } + #[inline(always)] + fn reset_counter(&mut self) { + self.cnt.reset(); + } + #[inline(always)] + fn set_prescaler(&mut self, psc: u16) { + self.psc.write(|w| unsafe { w.psc().bits(psc) } ); + } + #[inline(always)] + fn read_prescaler(&self) -> u16 { + self.psc.read().psc().bits() + } + #[inline(always)] + fn trigger_update(&mut self) { + // Sets the URS bit to prevent an interrupt from being triggered by + // the UG bit + self.cr1.modify(|_, w| w.urs().set_bit()); + self.egr.write(|w| w.ug().set_bit()); + self.cr1.modify(|_, w| w.urs().clear_bit()); + } + #[inline(always)] + fn clear_interrupt_flag(&mut self, event: Event) { + self.sr.write(|w| unsafe { w.bits(0xffff & !event.bits()) }); + } + #[inline(always)] + fn listen_interrupt(&mut self, event: Event, b: bool) { + self.dier.modify(|r, w| unsafe { w.bits( + if b { + r.bits() | event.bits() + } else { + r.bits() & !event.bits() + } + ) }); + } + #[inline(always)] + fn get_interrupt_flag(&self) -> Event { + Event::from_bits_truncate(self.sr.read().bits()) + } + #[inline(always)] + fn read_count(&self) -> Self::Width { + self.cnt.read().bits() as Self::Width + } + #[inline(always)] + fn cr1_reset(&mut self) { + self.cr1.reset(); + } + #[inline(always)] + fn stop_in_debug(&mut self, dbg: &mut DBG, state: bool) { + dbg.$dbg_timX_reg.modify(|_, w| w.$dbg_timX_stop().bit(state)); + } + } + + $(impl MasterTimer for $TIM { + type Mms = pac::$timbase::cr2::MMS_A; + fn master_mode(&mut self, mode: Self::Mms) { + self.cr2.modify(|_,w| w.mms().variant(mode)); + } + })? + + $(impl OnePulseMode for $TIM { + fn start_one_pulse(&mut self) { + self.cr1.modify(|_, w| w.$opm().set_bit().cen().set_bit()); + } + })? + )+ + } +} + +impl Timer { + /// Initialize timer + pub fn new(tim: TIM, clocks: &Clocks) -> Self { + unsafe { + //NOTE(unsafe) this reference will only be used for atomic writes with no side effects + let rcc = &(*pac::RCC::ptr()); + // Enable and reset the timer peripheral + TIM::enable(rcc); + TIM::reset(rcc); + } + + Self { + clk: TIM::timer_clock(clocks), + tim, + } + } + + pub fn configure(&mut self, clocks: &Clocks) { + self.clk = TIM::timer_clock(clocks); + } + + pub fn counter_hz(self) -> CounterHz { + CounterHz(self) + } + + pub fn release(self) -> TIM { + self.tim + } + + /// Starts listening for an `event` + /// + /// Note, you will also have to enable the TIM2 interrupt in the NVIC to start + /// receiving events. + pub fn listen(&mut self, event: Event) { + self.tim.listen_interrupt(event, true); + } + + /// Clears interrupt associated with `event`. + /// + /// If the interrupt is not cleared, it will immediately retrigger after + /// the ISR has finished. + pub fn clear_interrupt(&mut self, event: Event) { + self.tim.clear_interrupt_flag(event); + } + + pub fn get_interrupt(&mut self) -> Event { + self.tim.get_interrupt_flag() + } + + /// Stops listening for an `event` + pub fn unlisten(&mut self, event: Event) { + self.tim.listen_interrupt(event, false); + } + + /// Stopping timer in debug mode can cause troubles when sampling the signal + pub fn stop_in_debug(&mut self, dbg: &mut DBG, state: bool) { + self.tim.stop_in_debug(dbg, state); + } +} + +impl Timer { + pub fn set_master_mode(&mut self, mode: TIM::Mms) { + self.tim.master_mode(mode) + } +} + +/// Timer wrapper for fixed precision timers. +/// +/// Uses `fugit::TimerDurationU32` for most of operations +pub struct FTimer { + tim: TIM, +} + +/// `FTimer` with precision of 1 μs (1 MHz sampling) +pub type FTimerUs = FTimer; + +/// `FTimer` with precision of 1 ms (1 kHz sampling) +/// +/// NOTE: don't use this if your system frequency more than 65 MHz +pub type FTimerMs = FTimer; + +impl FTimer { + /// Initialize timer + pub fn new(tim: TIM, clocks: &Clocks) -> Self { + unsafe { + //NOTE(unsafe) this reference will only be used for atomic writes with no side effects + let rcc = &(*pac::RCC::ptr()); + // Enable and reset the timer peripheral + TIM::enable(rcc); + TIM::reset(rcc); + } + + let mut t = Self { tim }; + t.configure(clocks); + t + } + + /// Calculate prescaler depending on `Clocks` state + pub fn configure(&mut self, clocks: &Clocks) { + let clk = TIM::timer_clock(clocks); + assert!(clk.raw() % FREQ == 0); + let psc = clk.raw() / FREQ; + self.tim.set_prescaler(u16::try_from(psc - 1).unwrap()); + } + + /// Creates `Counter` that implements [embedded_hal_02::timer::CountDown] + pub fn counter(self) -> Counter { + Counter(self) + } + + /// Creates `Delay` that implements [embedded_hal_02::delay::Delay] + pub fn delay(self) -> Delay { + Delay(self) + } + + /// Releases the TIM peripheral + pub fn release(self) -> TIM { + self.tim + } + + /// Starts listening for an `event` + /// + /// Note, you will also have to enable the TIMX interrupt in the NVIC to start + /// receiving events. + pub fn listen(&mut self, event: Event) { + self.tim.listen_interrupt(event, true); + } + + /// Clears interrupt associated with `event`. + /// + /// If the interrupt is not cleared, it will immediately retrigger after + /// the ISR has finished. + pub fn clear_interrupt(&mut self, event: Event) { + self.tim.clear_interrupt_flag(event); + } + + pub fn get_interrupt(&mut self) -> Event { + self.tim.get_interrupt_flag() + } + + /// Stops listening for an `event` + pub fn unlisten(&mut self, event: Event) { + self.tim.listen_interrupt(event, false); + } + + /// Stopping timer in debug mode can cause troubles when sampling the signal + pub fn stop_in_debug(&mut self, dbg: &mut DBG, state: bool) { + self.tim.stop_in_debug(dbg, state); + } +} + +impl FTimer { + pub fn set_master_mode(&mut self, mode: TIM::Mms) { + self.tim.master_mode(mode) + } +} + +impl FTimer { + /// Creates `OpmDelay` that implements [embedded_hal_02::delay::Delay] + pub fn onepulsemode_delay(self) -> OpmDelay { + OpmDelay(self) + } +} + +#[inline(always)] +const fn compute_arr_presc(freq: u32, clock: u32) -> (u16, u32) { + let ticks = clock / freq; + let psc = (ticks - 1) / (1 << 16); + let arr = ticks / (psc + 1) - 1; + (psc as u16, arr) +} + +hal!( + pac::TIM1: [Timer1, u16, apb_fz2, dbg_timer1_stop, m: tim1, opm: opm,], +); + +#[cfg(any(feature = "py32f030", feature = "py32f003"))] +hal!( + pac::TIM3: [Timer3, u16, apb_fz1, dbg_timer3_stop, m: tim3, opm: opm,], + pac::TIM17: [Timer17, u16, apb_fz2, dbg_timer17_stop, opm: opm,], +); + +#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] +hal!( + pac::TIM16: [Timer16, u16, apb_fz2, dbg_timer16_stop, opm: opm,], +); + +#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002b"))] +hal!( + pac::TIM14: [Timer14, u16, apb_fz2, dbg_timer14_stop,], +); diff --git a/src/timer/counter.rs b/src/timer/counter.rs new file mode 100644 index 0000000..4931a8e --- /dev/null +++ b/src/timer/counter.rs @@ -0,0 +1,374 @@ +use super::{compute_arr_presc, Error, Event, FTimer, Instance, SysEvent, Timer}; +use crate::pac::SYST; +use core::convert::TryFrom; +use core::ops::{Deref, DerefMut}; +use fugit::{HertzU32 as Hertz, MicrosDurationU32, TimerDurationU32, TimerInstantU32}; + +/// Hardware timers +pub struct CounterHz(pub(super) Timer); + +impl Deref for CounterHz { + type Target = Timer; + fn deref(&self) -> &Self::Target { + &self.0 + } +} + +impl DerefMut for CounterHz { + fn deref_mut(&mut self) -> &mut Self::Target { + &mut self.0 + } +} + +impl CounterHz { + /// Releases the TIM peripheral + pub fn release(mut self) -> Timer { + // stop timer + self.tim.cr1_reset(); + self.0 + } +} + +impl CounterHz { + pub fn start(&mut self, timeout: Hertz) -> Result<(), Error> { + // pause + self.tim.disable_counter(); + + self.tim.clear_interrupt_flag(Event::Update); + + // reset counter + self.tim.reset_counter(); + + let (psc, arr) = compute_arr_presc(timeout.raw(), self.clk.raw()); + self.tim.set_prescaler(psc); + self.tim.set_auto_reload(arr)?; + + // Trigger update event to load the registers + self.tim.trigger_update(); + + // start counter + self.tim.enable_counter(); + + Ok(()) + } + + pub fn wait(&mut self) -> nb::Result<(), Error> { + if self.tim.get_interrupt_flag().contains(Event::Update) { + self.tim.clear_interrupt_flag(Event::Update); + Ok(()) + } else { + Err(nb::Error::WouldBlock) + } + } + + pub fn cancel(&mut self) -> Result<(), Error> { + if !self.tim.is_counter_enabled() { + return Err(Error::Disabled); + } + + // disable counter + self.tim.disable_counter(); + Ok(()) + } + + /// Restarts the timer in count down mode with user-defined prescaler and auto-reload register + pub fn start_raw(&mut self, psc: u16, arr: u16) { + // pause + self.tim.disable_counter(); + + self.tim.set_prescaler(psc); + + self.tim.set_auto_reload(arr as u32).unwrap(); + + // Trigger an update event to load the prescaler value to the clock + self.tim.trigger_update(); + + // start counter + self.tim.enable_counter(); + } + + /// Retrieves the content of the prescaler register. The real prescaler is this value + 1. + pub fn psc(&self) -> u16 { + self.tim.read_prescaler() + } + + /// Retrieves the value of the auto-reload register. + pub fn arr(&self) -> u16 { + TIM::read_auto_reload() as u16 + } + + /// Resets the counter + pub fn reset(&mut self) { + // Sets the URS bit to prevent an interrupt from being triggered by + // the UG bit + self.tim.trigger_update(); + } + + /// Returns the number of microseconds since the last update event. + /// *NOTE:* This method is not a very good candidate to keep track of time, because + /// it is very easy to lose an update event. + pub fn now(&self) -> MicrosDurationU32 { + let psc = self.tim.read_prescaler() as u32; + + // freq_divider is always bigger than 0, since (psc + 1) is always less than + // timer_clock + let freq_divider = (self.clk.raw() / (psc + 1)) as u64; + let cnt: u32 = self.tim.read_count().into(); + let cnt = cnt as u64; + + // It is safe to make this cast, because the maximum timer period in this HAL is + // 1s (1Hz), then 1 second < (2^32 - 1) microseconds + MicrosDurationU32::from_ticks(u32::try_from(1_000_000 * cnt / freq_divider).unwrap()) + } +} + +/// Periodic non-blocking timer that implements [embedded_hal_02::timer::CountDown] +pub struct Counter(pub(super) FTimer); + +impl Deref for Counter { + type Target = FTimer; + fn deref(&self) -> &Self::Target { + &self.0 + } +} + +impl DerefMut for Counter { + fn deref_mut(&mut self) -> &mut Self::Target { + &mut self.0 + } +} + +/// `Counter` with precision of 1 μs (1 MHz sampling) +pub type CounterUs = Counter; + +/// `Counter` with precision of of 1 ms (1 kHz sampling) +/// +/// NOTE: don't use this if your system frequency more than 65 MHz +pub type CounterMs = Counter; + +impl Counter { + /// Releases the TIM peripheral + pub fn release(mut self) -> FTimer { + // stop counter + self.tim.cr1_reset(); + self.0 + } + + pub fn now(&self) -> TimerInstantU32 { + TimerInstantU32::from_ticks(self.tim.read_count().into()) + } + + pub fn start(&mut self, timeout: TimerDurationU32) -> Result<(), Error> { + // pause + self.tim.disable_counter(); + + self.tim.clear_interrupt_flag(Event::Update); + + // reset counter + self.tim.reset_counter(); + + self.tim.set_auto_reload(timeout.ticks() - 1)?; + + // Trigger update event to load the registers + self.tim.trigger_update(); + + // start counter + self.tim.enable_counter(); + + Ok(()) + } + + pub fn wait(&mut self) -> nb::Result<(), Error> { + if self.tim.get_interrupt_flag().contains(Event::Update) { + self.tim.clear_interrupt_flag(Event::Update); + Ok(()) + } else { + Err(nb::Error::WouldBlock) + } + } + + pub fn cancel(&mut self) -> Result<(), Error> { + if !self.tim.is_counter_enabled() { + return Err(Error::Disabled); + } + + // disable counter + self.tim.disable_counter(); + Ok(()) + } +} + +impl fugit_timer::Timer for Counter { + type Error = Error; + + fn now(&mut self) -> TimerInstantU32 { + Self::now(self) + } + + fn start(&mut self, duration: TimerDurationU32) -> Result<(), Self::Error> { + self.start(duration) + } + + fn cancel(&mut self) -> Result<(), Self::Error> { + self.cancel() + } + + fn wait(&mut self) -> nb::Result<(), Self::Error> { + self.wait() + } +} + +impl Timer { + /// Creates [SysCounterHz] which takes [Hertz] as Duration + pub fn counter_hz(self) -> SysCounterHz { + SysCounterHz(self) + } + + /// Creates [SysCounter] with custom precision (core frequency recommended is known) + pub fn counter(self) -> SysCounter { + SysCounter(self) + } + + /// Creates [SysCounter] 1 microsecond precision + pub fn counter_us(self) -> SysCounterUs { + SysCounter(self) + } +} + +/// Hardware timers +pub struct SysCounterHz(Timer); + +impl Deref for SysCounterHz { + type Target = Timer; + fn deref(&self) -> &Self::Target { + &self.0 + } +} + +impl DerefMut for SysCounterHz { + fn deref_mut(&mut self) -> &mut Self::Target { + &mut self.0 + } +} + +impl SysCounterHz { + pub fn start(&mut self, timeout: Hertz) -> Result<(), Error> { + let rvr = self.clk.raw() / timeout.raw() - 1; + + if rvr >= (1 << 24) { + return Err(Error::WrongAutoReload); + } + + self.tim.set_reload(rvr); + self.tim.clear_current(); + self.tim.enable_counter(); + + Ok(()) + } + + pub fn wait(&mut self) -> nb::Result<(), Error> { + if self.tim.has_wrapped() { + Ok(()) + } else { + Err(nb::Error::WouldBlock) + } + } + + pub fn cancel(&mut self) -> Result<(), Error> { + if !self.tim.is_counter_enabled() { + return Err(Error::Disabled); + } + + self.tim.disable_counter(); + Ok(()) + } +} + +pub type SysCounterUs = SysCounter<1_000_000>; + +/// SysTick timer with precision of 1 μs (1 MHz sampling) +pub struct SysCounter(Timer); + +impl Deref for SysCounter { + type Target = Timer; + fn deref(&self) -> &Self::Target { + &self.0 + } +} + +impl DerefMut for SysCounter { + fn deref_mut(&mut self) -> &mut Self::Target { + &mut self.0 + } +} + +impl SysCounter { + /// Starts listening for an `event` + pub fn listen(&mut self, event: SysEvent) { + match event { + SysEvent::Update => self.tim.enable_interrupt(), + } + } + + /// Stops listening for an `event` + pub fn unlisten(&mut self, event: SysEvent) { + match event { + SysEvent::Update => self.tim.disable_interrupt(), + } + } + + pub fn now(&self) -> TimerInstantU32 { + TimerInstantU32::from_ticks(SYST::get_current() / (self.clk.raw() / FREQ)) + } + + pub fn start(&mut self, timeout: TimerDurationU32) -> Result<(), Error> { + let rvr = timeout.ticks() * (self.clk.raw() / FREQ) - 1; + + if rvr >= (1 << 24) { + return Err(Error::WrongAutoReload); + } + + self.tim.set_reload(rvr); + self.tim.clear_current(); + self.tim.enable_counter(); + + Ok(()) + } + + pub fn wait(&mut self) -> nb::Result<(), Error> { + if self.tim.has_wrapped() { + Ok(()) + } else { + Err(nb::Error::WouldBlock) + } + } + + pub fn cancel(&mut self) -> Result<(), Error> { + if !self.tim.is_counter_enabled() { + return Err(Error::Disabled); + } + + self.tim.disable_counter(); + Ok(()) + } +} + +impl fugit_timer::Timer for SysCounter { + type Error = Error; + + fn now(&mut self) -> TimerInstantU32 { + Self::now(self) + } + + fn start(&mut self, duration: TimerDurationU32) -> Result<(), Self::Error> { + self.start(duration) + } + + fn wait(&mut self) -> nb::Result<(), Self::Error> { + self.wait() + } + + fn cancel(&mut self) -> Result<(), Self::Error> { + self.cancel() + } +} diff --git a/src/timer/delay.rs b/src/timer/delay.rs new file mode 100644 index 0000000..ef19fc5 --- /dev/null +++ b/src/timer/delay.rs @@ -0,0 +1,214 @@ +//! Delays + +use super::{Event, FTimer, Instance, OnePulseMode, Timer}; +use core::ops::{Deref, DerefMut}; +use cortex_m::peripheral::SYST; +use fugit::{MicrosDurationU32, TimerDurationU32}; + +/// Timer as a delay provider (SysTick by default) +pub struct SysDelay(Timer); + +impl Deref for SysDelay { + type Target = Timer; + fn deref(&self) -> &Self::Target { + &self.0 + } +} + +impl DerefMut for SysDelay { + fn deref_mut(&mut self) -> &mut Self::Target { + &mut self.0 + } +} + +impl SysDelay { + /// Releases the timer resource + pub fn release(self) -> Timer { + self.0 + } +} + +impl Timer { + pub fn delay(self) -> SysDelay { + SysDelay(self) + } +} + +impl SysDelay { + pub fn delay(&mut self, us: MicrosDurationU32) { + // The SysTick Reload Value register supports values between 1 and 0x00FFFFFF. + const MAX_RVR: u32 = 0x00FF_FFFF; + + let mut total_rvr = us.ticks() * (self.clk.raw() / 1_000_000); + + while total_rvr != 0 { + let current_rvr = total_rvr.min(MAX_RVR); + + self.tim.set_reload(current_rvr); + self.tim.clear_current(); + self.tim.enable_counter(); + + // Update the tracking variable while we are waiting... + total_rvr -= current_rvr; + + while !self.tim.has_wrapped() {} + + self.tim.disable_counter(); + } + } +} + +/// Periodic non-blocking timer that implements [embedded_hal_02::blocking::delay] traits +pub struct Delay(pub(super) FTimer); + +impl Deref for Delay { + type Target = FTimer; + fn deref(&self) -> &Self::Target { + &self.0 + } +} + +impl DerefMut for Delay { + fn deref_mut(&mut self) -> &mut Self::Target { + &mut self.0 + } +} + +/// `Delay` with precision of 1 μs (1 MHz sampling) +pub type DelayUs = Delay; + +/// `Delay` with precision of 1 ms (1 kHz sampling) +/// +/// NOTE: don't use this if your system frequency more than 65 MHz +pub type DelayMs = Delay; + +impl Delay { + /// Sleep for given time + pub fn delay(&mut self, time: TimerDurationU32) { + let mut ticks = time.ticks().max(1) - 1; + while ticks != 0 { + let reload = ticks.min(TIM::max_auto_reload()); + + // Write Auto-Reload Register (ARR) + unsafe { + self.tim.set_auto_reload_unchecked(reload); + } + + // Trigger update event (UEV) in the event generation register (EGR) + // in order to immediately apply the config + self.tim.trigger_update(); + + // enable the counter. + self.tim.enable_counter(); + + // Update the tracking variable while we are waiting... + ticks -= reload; + // Wait for update to happen + while self.tim.get_interrupt_flag() != Event::Update { /* wait */ } + // disable the counter + self.tim.disable_counter(); + } + } + + pub fn max_delay(&self) -> TimerDurationU32 { + TimerDurationU32::from_ticks(TIM::max_auto_reload()) + } + + /// Releases the TIM peripheral + pub fn release(mut self) -> FTimer { + // stop counter + self.tim.cr1_reset(); + self.0 + } +} + +/// Periodic non-blocking timer that implements [embedded_hal_02::blocking::delay] traits +pub struct OpmDelay(pub(super) FTimer); + +impl Deref for OpmDelay { + type Target = FTimer; + fn deref(&self) -> &Self::Target { + &self.0 + } +} + +impl DerefMut for OpmDelay { + fn deref_mut(&mut self) -> &mut Self::Target { + &mut self.0 + } +} + +/// `Delay` with precision of 1 μs (1 MHz sampling) +pub type OpmDelayUs = OpmDelay; + +/// `Delay` with precision of 1 ms (1 kHz sampling) +/// +/// NOTE: don't use this if your system frequency more than 65 MHz +pub type OpmDelayMs = OpmDelay; + +impl OpmDelay { + fn delay(&mut self, time: TimerDurationU32) { + let mut ticks = time.ticks().max(1) - 1; + while ticks != 0 { + let reload = ticks.min(TIM::max_auto_reload()); + + // Write Auto-Reload Register (ARR) + unsafe { + self.tim.set_auto_reload_unchecked(reload); + } + + // Trigger update event (UEV) in the event generation register (EGR) + // in order to immediately apply the config + self.tim.trigger_update(); + + // Configure the counter in one-pulse mode (counter stops counting at + // the next updateevent, clearing the CEN bit) and enable the counter. + self.tim.start_one_pulse(); + + // Update the tracking variable while we are waiting... + ticks -= reload; + // Wait for CEN bit to clear + while self.tim.is_counter_enabled() { /* wait */ } + } + } + + pub fn max_delay(&self) -> TimerDurationU32 { + TimerDurationU32::from_ticks(TIM::max_auto_reload()) + } + + /// Releases the TIM peripheral + pub fn release(mut self) -> FTimer { + // stop counter + self.tim.cr1_reset(); + self.0 + } +} + +impl fugit_timer::Delay for Delay { + type Error = core::convert::Infallible; + + fn delay(&mut self, duration: TimerDurationU32) -> Result<(), Self::Error> { + self.delay(duration); + Ok(()) + } +} + +impl fugit_timer::Delay + for OpmDelay +{ + type Error = core::convert::Infallible; + + fn delay(&mut self, duration: TimerDurationU32) -> Result<(), Self::Error> { + self.delay(duration); + Ok(()) + } +} + +impl fugit_timer::Delay<1_000_000> for SysDelay { + type Error = core::convert::Infallible; + + fn delay(&mut self, duration: MicrosDurationU32) -> Result<(), Self::Error> { + self.delay(duration); + Ok(()) + } +} diff --git a/src/timer/hal_02.rs b/src/timer/hal_02.rs new file mode 100644 index 0000000..d8f1199 --- /dev/null +++ b/src/timer/hal_02.rs @@ -0,0 +1,306 @@ +//! Delay implementation based on general-purpose 16 bit timers and System timer (SysTick). +//! +//! TIM1 and TIM3 are a general purpose 16-bit auto-reload up/downcounter with +//! a 16-bit prescaler. + +use crate::time::Hertz; +use embedded_hal_02::{ + blocking::delay::{DelayMs, DelayUs}, + timer::{Cancel, CountDown, Periodic}, +}; +use fugit::{ExtU32, TimerDurationU32}; +use void::Void; + +use super::{Counter, CounterHz, Delay, Error, Instance, SysCounter, SysCounterHz, SysDelay}; + +impl DelayUs for SysDelay { + fn delay_us(&mut self, us: u32) { + self.delay(us.micros()) + } +} + +impl DelayMs for SysDelay { + fn delay_ms(&mut self, ms: u32) { + self.delay_us(ms * 1_000); + } +} + +impl DelayUs for SysDelay { + fn delay_us(&mut self, us: u16) { + self.delay_us(us as u32) + } +} + +impl DelayMs for SysDelay { + fn delay_ms(&mut self, ms: u16) { + self.delay_ms(ms as u32); + } +} + +impl DelayUs for SysDelay { + fn delay_us(&mut self, us: u8) { + self.delay_us(us as u32) + } +} + +impl DelayMs for SysDelay { + fn delay_ms(&mut self, ms: u8) { + self.delay_ms(ms as u32); + } +} + +impl Periodic for CounterHz {} +impl Periodic for SysCounterHz {} +impl Periodic for SysCounter {} + +impl CountDown for SysCounterHz { + type Time = Hertz; + + fn start(&mut self, timeout: T) + where + T: Into, + { + self.start(timeout.into()).unwrap() + } + + fn wait(&mut self) -> nb::Result<(), Void> { + match self.wait() { + Err(nb::Error::WouldBlock) => Err(nb::Error::WouldBlock), + _ => Ok(()), + } + } +} + +impl Cancel for SysCounterHz { + type Error = Error; + + fn cancel(&mut self) -> Result<(), Self::Error> { + self.cancel() + } +} + +impl CountDown for CounterHz { + type Time = Hertz; + + fn start(&mut self, timeout: T) + where + T: Into, + { + self.start(timeout.into()).unwrap() + } + + fn wait(&mut self) -> nb::Result<(), Void> { + match self.wait() { + Err(nb::Error::WouldBlock) => Err(nb::Error::WouldBlock), + _ => Ok(()), + } + } +} + +impl Cancel for CounterHz { + type Error = Error; + + fn cancel(&mut self) -> Result<(), Self::Error> { + self.cancel() + } +} + +impl CountDown for SysCounter { + type Time = TimerDurationU32; + + fn start(&mut self, timeout: T) + where + T: Into, + { + self.start(timeout.into()).unwrap() + } + + fn wait(&mut self) -> nb::Result<(), Void> { + match self.wait() { + Err(nb::Error::WouldBlock) => Err(nb::Error::WouldBlock), + _ => Ok(()), + } + } +} + +impl Cancel for SysCounter { + type Error = Error; + + fn cancel(&mut self) -> Result<(), Self::Error> { + self.cancel() + } +} + +// impl embedded_hal_02::PwmPin for PwmChannel { +// type Duty = u16; + +// fn disable(&mut self) { +// self.disable() +// } +// fn enable(&mut self) { +// self.enable() +// } +// fn get_duty(&self) -> Self::Duty { +// self.get_duty() +// } +// fn get_max_duty(&self) -> Self::Duty { +// self.get_max_duty() +// } +// fn set_duty(&mut self, duty: Self::Duty) { +// self.set_duty(duty) +// } +// } + +// impl embedded_hal_02::Pwm for PwmHz +// where +// TIM: Instance + WithPwm, +// REMAP: Remap, +// PINS: Pins, +// { +// type Channel = Channel; +// type Duty = u16; +// type Time = Hertz; + +// fn enable(&mut self, channel: Self::Channel) { +// self.enable(channel) +// } + +// fn disable(&mut self, channel: Self::Channel) { +// self.disable(channel) +// } + +// fn get_duty(&self, channel: Self::Channel) -> Self::Duty { +// self.get_duty(channel) +// } + +// fn set_duty(&mut self, channel: Self::Channel, duty: Self::Duty) { +// self.set_duty(channel, duty) +// } + +// /// If `0` returned means max_duty is 2^16 +// fn get_max_duty(&self) -> Self::Duty { +// self.get_max_duty() +// } + +// fn get_period(&self) -> Self::Time { +// self.get_period() +// } + +// fn set_period(&mut self, period: T) +// where +// T: Into, +// { +// self.set_period(period.into()) +// } +// } + +impl DelayUs for Delay { + /// Sleep for `us` microseconds + fn delay_us(&mut self, us: u32) { + self.delay(us.micros()) + } +} + +impl DelayMs for Delay { + /// Sleep for `ms` milliseconds + fn delay_ms(&mut self, ms: u32) { + self.delay(ms.millis()) + } +} + +impl DelayUs for Delay { + /// Sleep for `us` microseconds + fn delay_us(&mut self, us: u16) { + self.delay((us as u32).micros()) + } +} +impl DelayMs for Delay { + /// Sleep for `ms` milliseconds + fn delay_ms(&mut self, ms: u16) { + self.delay((ms as u32).millis()) + } +} + +impl DelayUs for Delay { + /// Sleep for `us` microseconds + fn delay_us(&mut self, us: u8) { + self.delay((us as u32).micros()) + } +} +impl DelayMs for Delay { + /// Sleep for `ms` milliseconds + fn delay_ms(&mut self, ms: u8) { + self.delay((ms as u32).millis()) + } +} + +impl Periodic for Counter {} + +impl CountDown for Counter { + type Time = TimerDurationU32; + + fn start(&mut self, timeout: T) + where + T: Into, + { + self.start(timeout.into()).unwrap() + } + + fn wait(&mut self) -> nb::Result<(), Void> { + match self.wait() { + Err(nb::Error::WouldBlock) => Err(nb::Error::WouldBlock), + _ => Ok(()), + } + } +} + +impl Cancel for Counter { + type Error = Error; + + fn cancel(&mut self) -> Result<(), Self::Error> { + self.cancel() + } +} + +// impl embedded_hal_02::Pwm for Pwm +// where +// TIM: Instance + WithPwm, +// REMAP: Remap, +// PINS: Pins, +// { +// type Channel = Channel; +// type Duty = u16; +// type Time = TimerDurationU32; + +// fn enable(&mut self, channel: Self::Channel) { +// self.enable(channel) +// } + +// fn disable(&mut self, channel: Self::Channel) { +// self.disable(channel) +// } + +// fn get_duty(&self, channel: Self::Channel) -> Self::Duty { +// self.get_duty(channel) +// } + +// fn set_duty(&mut self, channel: Self::Channel, duty: Self::Duty) { +// self.set_duty(channel, duty) +// } + +// /// If `0` returned means max_duty is 2^16 +// fn get_max_duty(&self) -> Self::Duty { +// self.get_max_duty() +// } + +// fn get_period(&self) -> Self::Time { +// self.get_period() +// } + +// fn set_period(&mut self, period: T) +// where +// T: Into, +// { +// self.set_period(period.into()) +// } +// } diff --git a/src/timer/hal_1.rs b/src/timer/hal_1.rs new file mode 100644 index 0000000..58eed9b --- /dev/null +++ b/src/timer/hal_1.rs @@ -0,0 +1,47 @@ +//! Delay implementation based on general-purpose 16 bit timers and System timer (SysTick). +//! +//! TIM1 and TIM3 are a general purpose 16-bit auto-reload up/downcounter with +//! a 16-bit prescaler. + +use embedded_hal::delay::DelayNs; + +use super::{Delay, Instance, SysDelay}; +use fugit::ExtU32Ceil; + +impl DelayNs for SysDelay { + fn delay_ns(&mut self, ns: u32) { + self.delay(ns.nanos_at_least()); + } + + fn delay_ms(&mut self, ms: u32) { + self.delay(ms.millis_at_least()); + } +} + +impl DelayNs for Delay { + fn delay_ns(&mut self, ns: u32) { + self.delay(ns.micros_at_least()); + } + + fn delay_us(&mut self, us: u32) { + self.delay(us.micros_at_least()); + } + + fn delay_ms(&mut self, ms: u32) { + self.delay(ms.millis_at_least()); + } +} + +// impl embedded_hal::pwm::ErrorType for PwmChannel { +// type Error = Infallible; +// } + +// impl embedded_hal::pwm::SetDutyCycle for PwmChannel { +// fn max_duty_cycle(&self) -> u16 { +// self.get_max_duty() +// } +// fn set_duty_cycle(&mut self, duty: u16) -> Result<(), Self::Error> { +// self.set_duty(duty); +// Ok(()) +// } +// } diff --git a/src/timer/monotonic.rs b/src/timer/monotonic.rs new file mode 100644 index 0000000..a940aed --- /dev/null +++ b/src/timer/monotonic.rs @@ -0,0 +1,153 @@ +//! RTIC Monotonic implementation + +use super::{FTimer, Instance}; +use crate::rcc::Clocks; +use core::ops::{Deref, DerefMut}; +pub use fugit::{self, ExtU32}; +use rtic_monotonic::Monotonic; + +pub struct MonoTimer { + timer: FTimer, + ovf: u32, +} + +impl Deref for MonoTimer { + type Target = FTimer; + fn deref(&self) -> &Self::Target { + &self.timer + } +} + +impl DerefMut for MonoTimer { + fn deref_mut(&mut self) -> &mut Self::Target { + &mut self.timer + } +} + +/// `MonoTimer` with precision of 1 μs (1 MHz sampling) +pub type MonoTimerUs = MonoTimer; + +impl MonoTimer { + /// Releases the TIM peripheral + pub fn release(mut self) -> FTimer { + // stop counter + self.tim.cr1_reset(); + self.timer + } +} + +pub trait MonoTimerExt: Sized { + fn monotonic(self, clocks: &Clocks) -> MonoTimer; + fn monotonic_us(self, clocks: &Clocks) -> MonoTimer { + self.monotonic::<1_000_000>(clocks) + } +} + +macro_rules! mono { + ($TIM:ty) => { + impl MonoTimerExt for $TIM { + fn monotonic(self, clocks: &Clocks) -> MonoTimer { + FTimer::new(self, clocks).monotonic() + } + } + + impl FTimer<$TIM, FREQ> { + pub fn monotonic(self) -> MonoTimer<$TIM, FREQ> { + MonoTimer::<$TIM, FREQ>::_new(self) + } + } + + impl MonoTimer<$TIM, FREQ> { + fn _new(timer: FTimer<$TIM, FREQ>) -> Self { + // Set auto-reload value. + timer.tim.arr.write(|w| unsafe { w.arr().bits(u16::MAX) }); + // Generate interrupt on overflow. + timer.tim.egr.write(|w| w.ug().set_bit()); + + // Start timer. + // Clear interrupt flag. + timer.tim.sr.modify(|_, w| w.uif().clear_bit()); + timer.tim.cr1.modify(|_, w| { + // Enable counter. + w.cen().set_bit(); + // Overflow should trigger update event. + w.udis().clear_bit(); + // Only overflow triggers interrupt. + w.urs().set_bit() + }); + + Self { timer, ovf: 0 } + } + } + + impl Monotonic for MonoTimer<$TIM, FREQ> { + type Instant = fugit::TimerInstantU32; + type Duration = fugit::TimerDurationU32; + + unsafe fn reset(&mut self) { + self.tim.dier.modify(|_, w| w.cc1ie().set_bit()); + } + + #[inline(always)] + fn now(&mut self) -> Self::Instant { + let cnt = self.tim.cnt.read().cnt().bits() as u32; + + // If the overflow bit is set, we add this to the timer value. It means the `on_interrupt` + // has not yet happened, and we need to compensate here. + let ovf = if self.tim.sr.read().uif().bit_is_set() { + 0x10000 + } else { + 0 + }; + + Self::Instant::from_ticks(cnt.wrapping_add(ovf).wrapping_add(self.ovf)) + } + + fn set_compare(&mut self, instant: Self::Instant) { + let now = self.now(); + let cnt = self.tim.cnt.read().cnt().bits(); + + // Since the timer may or may not overflow based on the requested compare val, we check + // how many ticks are left. + let val = match instant.checked_duration_since(now) { + None => cnt.wrapping_add(0xffff), // In the past, RTIC will handle this + Some(x) if x.ticks() <= 0xffff => instant.duration_since_epoch().ticks() as u16, // Will not overflow + Some(_) => cnt.wrapping_add(0xffff), // Will overflow, run for as long as possible + }; + + self.tim.ccr1.write(|w| unsafe { w.ccr().bits(val) }); + } + + fn clear_compare_flag(&mut self) { + self.tim.sr.modify(|_, w| w.cc1if().clear_bit()); + } + + fn on_interrupt(&mut self) { + // If there was an overflow, increment the overflow counter. + if self.tim.sr.read().uif().bit_is_set() { + self.tim.sr.modify(|_, w| w.uif().clear_bit()); + + self.ovf += 0x10000; + } + } + + #[inline(always)] + fn zero() -> Self::Instant { + Self::Instant::from_ticks(0) + } + } + }; +} + +mono!(crate::pac::TIM1); + +#[cfg(any(feature = "py32f030", feature = "py32f003"))] +mono!(crate::pac::TIM3); +#[cfg(any(feature = "py32f030", feature = "py32f003"))] +mono!(crate::pac::TIM17); + +#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] +mono!(crate::pac::TIM16); + +#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002b"))] +mono!(crate::pac::TIM14); diff --git a/src/timer/pins.rs b/src/timer/pins.rs new file mode 100644 index 0000000..62276e2 --- /dev/null +++ b/src/timer/pins.rs @@ -0,0 +1,112 @@ +use crate::gpio::AF2; +use crate::gpio::{gpioa::*, gpiob::*, Alternate}; +use crate::pac; + +#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] +use crate::gpio::{AF1, AF13, AF14}; + +#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002b"))] +use crate::gpio::AF5; + +#[cfg(any(feature = "py32f030", feature = "py32f003"))] +use crate::gpio::{gpiof::*, AF0, AF4}; + +#[cfg(feature = "py32f002b")] +use crate::gpio::{gpioc::*, AF3}; + +// Output channels marker traits +pub trait PinC1 {} +pub trait PinC1N {} +pub trait PinC2 {} +pub trait PinC2N {} +pub trait PinC3 {} +pub trait PinC3N {} +pub trait PinC4 {} + +macro_rules! channel_impl { + ( $( $TIM:ty, $PINC:ident, $PINX:ident, $MODE:ident<$AF:ident>; )+ ) => { + $( + impl $PINC<$TIM> for $PINX<$MODE<$AF>> {} + )+ + }; +} + +#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] +channel_impl!( + pac::TIM1, PinC3, PA0, Alternate; + pac::TIM1, PinC1N, PA0, Alternate; + pac::TIM1, PinC4, PA1, Alternate; + pac::TIM1, PinC2N, PA1, Alternate; + pac::TIM1, PinC1, PA3, Alternate; + pac::TIM1, PinC1N, PA7, Alternate; + pac::TIM1, PinC2, PA13, Alternate; + pac::TIM1, PinC2N, PB0, Alternate; + pac::TIM1, PinC3N, PB1, Alternate; + pac::TIM1, PinC3, PB6, Alternate; +); + +#[cfg(any(feature = "py32f030", feature = "py32f002a"))] +channel_impl!( + pac::TIM1, PinC1, PA8, Alternate; + pac::TIM1, PinC2, PA9, Alternate; + pac::TIM1, PinC3, PA10, Alternate; + pac::TIM1, PinC4, PA11, Alternate; + pac::TIM1, PinC2, PB3, Alternate; +); + +#[cfg(any(feature = "py32f030", feature = "py32f003"))] +channel_impl!( + pac::TIM3, PinC1, PA2, Alternate; + pac::TIM3, PinC3, PA4, Alternate; + pac::TIM3, PinC2, PA5, Alternate; + pac::TIM3, PinC1, PA6, Alternate; + pac::TIM3, PinC2, PA7, Alternate; + pac::TIM3, PinC3, PB0, Alternate; + pac::TIM3, PinC4, PB1, Alternate; + pac::TIM3, PinC2, PB5, Alternate; + + pac::TIM14, PinC1, PA4, Alternate; + pac::TIM14, PinC1, PA7, Alternate; + pac::TIM14, PinC1, PB1, Alternate; + pac::TIM14, PinC1, PF0, Alternate; + pac::TIM14, PinC1, PF1, Alternate; + + pac::TIM16, PinC1, PA6, Alternate; + pac::TIM16, PinC1N, PB6, Alternate; + + pac::TIM17, PinC1, PA7, Alternate; + pac::TIM17, PinC1N, PB7, Alternate; +); + +#[cfg(feature = "py32f030")] +channel_impl!( + pac::TIM3, PinC1, PB4, Alternate; + + pac::TIM16, PinC1, PB8, Alternate; + + pac::TIM17, PinC1, PB8, Alternate; +); + +#[cfg(feature = "py32f002b")] +channel_impl!( + pac::TIM1, PinC1, PA0, Alternate; + pac::TIM1, PinC2, PA1, Alternate; + pac::TIM1, PinC4, PA2, Alternate; + pac::TIM1, PinC2, PA3, Alternate; + pac::TIM1, PinC3, PA4, Alternate; + pac::TIM1, PinC1, PA5, Alternate; + pac::TIM1, PinC4, PA7, Alternate; + pac::TIM1, PinC2, PB0, Alternate; + pac::TIM1, PinC3N, PB0, Alternate; + pac::TIM1, PinC2N, PB1, Alternate; + pac::TIM1, PinC4, PB1, Alternate; + pac::TIM1, PinC1N, PB2, Alternate; + pac::TIM1, PinC3, PB2, Alternate; + pac::TIM1, PinC3, PB5, Alternate; + pac::TIM1, PinC1N, PC0, Alternate; + + pac::TIM14, PinC1, PA4, Alternate; + pac::TIM14, PinC1, PA5, Alternate; + pac::TIM14, PinC1, PB5, Alternate; + pac::TIM14, PinC1, PB7, Alternate; +); diff --git a/src/timers.rs b/src/timers.rs deleted file mode 100644 index 8acccf7..0000000 --- a/src/timers.rs +++ /dev/null @@ -1,351 +0,0 @@ -//! API for the integrated timers -//! -//! This only implements basic functions, a lot of things are missing -//! -//! # Example -//! Blink the led with 1Hz -//! ``` no_run -//! use py32f0xx_hal as hal; -//! -//! use crate::hal::pac; -//! use crate::hal::prelude::*; -//! use crate::hal::time::*; -//! use crate::hal::timers::*; -//! use nb::block; -//! -//! let mut p = pac::Peripherals::take().unwrap(); -//! let rcc = p.RCC.configure().freeze(&mut p.FLASH); -//! -//! let gpioa = p.GPIOA.split(); -//! -//! let mut led = gpioa.pa1.into_push_pull_pull_output(); -//! -//! let mut timer = Timer::tim1(p.TIM1, Hertz(1), &rcc.clocks); -//! loop { -//! led.toggle(); -//! block!(timer.wait()).ok(); -//! } -//! ``` -use cortex_m::peripheral::syst::SystClkSource; -use cortex_m::peripheral::SYST; - -use crate::pac::RCC; -use crate::rcc::{BusTimerClock, Clocks, Enable, Rcc, Reset}; -use crate::time::Hertz; -use embedded_hal_02::timer::{CountDown, Periodic}; -use void::Void; - -/// Hardware timers -pub struct Timer { - clocks: Clocks, - tim: TIM, -} - -/// Interrupt events -pub enum Event { - /// Timer timed out / count down ended - TimeOut, -} - -impl Timer { - /// Configures the SYST clock as a periodic count down timer - pub fn syst(mut syst: SYST, timeout: T, rcc: &Rcc) -> Self - where - T: Into, - { - syst.set_clock_source(SystClkSource::Core); - let mut timer = Timer { - tim: syst, - clocks: rcc.clocks, - }; - timer.start(timeout); - timer - } - - /// Starts listening for an `event` - pub fn listen(&mut self, event: &Event) { - match event { - Event::TimeOut => self.tim.enable_interrupt(), - } - } - - /// Stops listening for an `event` - pub fn unlisten(&mut self, event: &Event) { - match event { - Event::TimeOut => self.tim.disable_interrupt(), - } - } -} - -/// Use the systick as a timer -/// -/// Be aware that intervals less than 4 Hertz may not function properly -impl CountDown for Timer { - type Time = Hertz; - - /// Start the timer with a `timeout` - fn start(&mut self, timeout: T) - where - T: Into, - { - let rvr = self.clocks.sysclk().0 / timeout.into().0 - 1; - - assert!(rvr < (1 << 24)); - - self.tim.set_reload(rvr); - self.tim.clear_current(); - self.tim.enable_counter(); - } - - /// Return `Ok` if the timer has wrapped - /// Automatically clears the flag and restarts the time - fn wait(&mut self) -> nb::Result<(), Void> { - if self.tim.has_wrapped() { - Ok(()) - } else { - Err(nb::Error::WouldBlock) - } - } -} - -impl Periodic for Timer {} - -pub trait Instance: crate::Sealed + Enable + Reset + BusTimerClock {} - -macro_rules! timers { - ($($TIM:ident: $tim:ident,)+) => { - $( - use crate::pac::$TIM; - impl Timer<$TIM> { - // XXX(why not name this `new`?) bummer: constructors need to have different names - // even if the `$TIM` are non overlapping (compare to the `free` function below - // which just works) - /// Configures a TIM peripheral as a periodic count down timer - pub fn $tim(tim: $TIM, timeout: T, clocks: &Clocks) -> Self - where - T: Into, - { - // enable and reset peripheral to a clean slate state - let rcc = unsafe { &(*RCC::ptr()) }; - $TIM::enable(rcc); - $TIM::reset(rcc); - - let mut timer = Timer { - clocks: *clocks, - tim, - }; - timer.start(timeout); - - timer - } - - /// Starts listening for an `event` - pub fn listen(&mut self, event: Event) { - match event { - Event::TimeOut => { - // Enable update event interrupt - self.tim.dier.write(|w| w.uie().set_bit()); - } - } - } - - /// Stops listening for an `event` - pub fn unlisten(&mut self, event: Event) { - match event { - Event::TimeOut => { - // Enable update event interrupt - self.tim.dier.write(|w| w.uie().clear_bit()); - } - } - } - - /// Releases the TIM peripheral - pub fn release(self) -> $TIM { - let rcc = unsafe { &(*crate::pac::RCC::ptr()) }; - // Pause counter - self.tim.cr1.modify(|_, w| w.cen().clear_bit()); - // Disable timer - $TIM::disable(rcc); - self.tim - } - - /// Clears interrupt flag - pub fn clear_irq(&mut self) { - self.tim.sr.modify(|_, w| w.uif().clear_bit()); - } - } - - impl CountDown for Timer<$TIM> { - type Time = Hertz; - - /// Start the timer with a `timeout` - fn start(&mut self, timeout: T) - where - T: Into, - { - // pause - self.tim.cr1.modify(|_, w| w.cen().clear_bit()); - // restart counter - self.tim.cnt.reset(); - - let frequency = timeout.into().0; - let ticks = $TIM::timer_clock(&self.clocks).0 / frequency; - - let psc = cast::u16((ticks - 1) / (1 << 16)).unwrap(); - self.tim.psc.write(|w| unsafe { w.psc().bits(psc) }); - - let arr = cast::u16(ticks / cast::u32(psc + 1)).unwrap(); - self.tim.arr.write(|w| unsafe { w.bits(cast::u32(arr)) }); - - // start counter - self.tim.cr1.modify(|_, w| w.cen().set_bit()); - } - - /// Return `Ok` if the timer has wrapped - /// Automatically clears the flag and restarts the time - fn wait(&mut self) -> nb::Result<(), Void> { - if self.tim.sr.read().uif().bit_is_clear() { - Err(nb::Error::WouldBlock) - } else { - self.tim.sr.modify(|_, w| w.uif().clear_bit()); - Ok(()) - } - } - } - - impl Periodic for Timer<$TIM> {} - )+ - } -} - -timers! { - TIM1: tim1, -} - -#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] -timers! { - TIM16: tim16, -} - -#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002b"))] -timers! { - TIM14: tim14, -} - -#[cfg(any(feature = "py32f030", feature = "py32f003"))] -timers! { - TIM3: tim3, - TIM17: tim17, -} - -use crate::gpio::AF2; -use crate::gpio::{gpioa::*, gpiob::*, Alternate}; - -#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] -use crate::gpio::{AF1, AF13, AF14}; - -#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002b"))] -use crate::gpio::AF5; - -#[cfg(any(feature = "py32f030", feature = "py32f003"))] -use crate::gpio::{gpiof::*, AF0, AF4}; - -#[cfg(feature = "py32f002b")] -use crate::gpio::{gpioc::*, AF3}; - -// Output channels marker traits -pub trait PinC1 {} -pub trait PinC1N {} -pub trait PinC2 {} -pub trait PinC2N {} -pub trait PinC3 {} -pub trait PinC3N {} -pub trait PinC4 {} - -macro_rules! channel_impl { - ( $( $TIM:ident, $PINC:ident, $PINX:ident, $MODE:ident<$AF:ident>; )+ ) => { - $( - impl $PINC<$TIM> for $PINX<$MODE<$AF>> {} - )+ - }; -} - -#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] -channel_impl!( - TIM1, PinC3, PA0, Alternate; - TIM1, PinC1N, PA0, Alternate; - TIM1, PinC4, PA1, Alternate; - TIM1, PinC2N, PA1, Alternate; - TIM1, PinC1, PA3, Alternate; - TIM1, PinC1N, PA7, Alternate; - TIM1, PinC2, PA13, Alternate; - TIM1, PinC2N, PB0, Alternate; - TIM1, PinC3N, PB1, Alternate; - TIM1, PinC3, PB6, Alternate; -); - -#[cfg(any(feature = "py32f030", feature = "py32f002a"))] -channel_impl!( - TIM1, PinC1, PA8, Alternate; - TIM1, PinC2, PA9, Alternate; - TIM1, PinC3, PA10, Alternate; - TIM1, PinC4, PA11, Alternate; - TIM1, PinC2, PB3, Alternate; -); - -#[cfg(any(feature = "py32f030", feature = "py32f003"))] -channel_impl!( - TIM3, PinC1, PA2, Alternate; - TIM3, PinC3, PA4, Alternate; - TIM3, PinC2, PA5, Alternate; - TIM3, PinC1, PA6, Alternate; - TIM3, PinC2, PA7, Alternate; - TIM3, PinC3, PB0, Alternate; - TIM3, PinC4, PB1, Alternate; - TIM3, PinC2, PB5, Alternate; - - TIM14, PinC1, PA4, Alternate; - TIM14, PinC1, PA7, Alternate; - TIM14, PinC1, PB1, Alternate; - TIM14, PinC1, PF0, Alternate; - TIM14, PinC1, PF1, Alternate; - - TIM16, PinC1, PA6, Alternate; - TIM16, PinC1N, PB6, Alternate; - - TIM17, PinC1, PA7, Alternate; - TIM17, PinC1N, PB7, Alternate; -); - -#[cfg(feature = "py32f030")] -channel_impl!( - TIM3, PinC1, PB4, Alternate; - - TIM16, PinC1, PB8, Alternate; - - TIM17, PinC1, PB8, Alternate; -); - -#[cfg(feature = "py32f002b")] -channel_impl!( - TIM1, PinC1, PA0, Alternate; - TIM1, PinC2, PA1, Alternate; - TIM1, PinC4, PA2, Alternate; - TIM1, PinC2, PA3, Alternate; - TIM1, PinC3, PA4, Alternate; - TIM1, PinC1, PA5, Alternate; - TIM1, PinC4, PA7, Alternate; - TIM1, PinC2, PB0, Alternate; - TIM1, PinC3N, PB0, Alternate; - TIM1, PinC2N, PB1, Alternate; - TIM1, PinC4, PB1, Alternate; - TIM1, PinC1N, PB2, Alternate; - TIM1, PinC3, PB2, Alternate; - TIM1, PinC3, PB5, Alternate; - TIM1, PinC1N, PC0, Alternate; - - TIM14, PinC1, PA4, Alternate; - TIM14, PinC1, PA5, Alternate; - TIM14, PinC1, PB5, Alternate; - TIM14, PinC1, PB7, Alternate; -); diff --git a/src/watchdog.rs b/src/watchdog.rs index b63a245..47418ff 100644 --- a/src/watchdog.rs +++ b/src/watchdog.rs @@ -31,12 +31,12 @@ //! use crate::hal::pac; //! use crate::hal::prelude::*; //! use crate::hal:watchdog::Watchdog; -//! use crate::hal:time::Hertz; //! //! let mut p = pac::Peripherals::take().unwrap(); +//! let mut rcc = p.RCC.configure().sysclk(8.MHz()).freeze(&mut p.FLASH); //! -//! let mut iwdg = Watchdog::new(p.iwdg); -//! iwdg.start(Hertz(100)); +//! let mut iwdg = Watchdog::new(&mut rcc, p.iwdg); +//! iwdg.start(100.Hz()); //! loop {} //! // Whoops, got stuck, the watchdog issues a reset after 10 ms //! iwdg.feed(); @@ -73,7 +73,7 @@ impl From for IwdgTimeout { /// /// It can also only represent values < 10000 Hertz fn from(hz: Hertz) -> Self { - let mut time = 32_768 / 4 / hz.0; + let mut time = 32_768 / 4 / hz.raw(); let mut psc = 0; let mut reload = 0; while psc < 7 { From 6190a8376f4b10573d6aad367ce549424f825749 Mon Sep 17 00:00:00 2001 From: Greg Green Date: Sun, 29 Dec 2024 13:58:15 -0800 Subject: [PATCH 08/11] Added build.rs to check that only 1 device is selected Fixed typos in Changelog Updated edition to 2021 Fixed authors in Cargo.toml --- CHANGELOG.md | 16 ++++++++++------ Cargo.toml | 29 +++++++++-------------------- README.md | 27 +++++++++++++++------------ build.rs | 36 ++++++++++++++++++++++++++++++++++++ src/rcc.rs | 2 +- src/timer.rs | 2 +- 6 files changed, 72 insertions(+), 40 deletions(-) create mode 100644 build.rs diff --git a/CHANGELOG.md b/CHANGELOG.md index 393dc91..4249abf 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -4,17 +4,19 @@ All notable changes to this project will be documented in this file. ## Unreleased -This version depends on py32-rs v1.1.2 or later +This version depends on py32-rs v0.2.0 or later ### Added +- added optional feature "rtic" to implement `rtic-monotonic::Monotonic` trait on timers. +- added optional feature "defmt" to implement `defmt::Format` trait on Errors in various modules +- added feature "with-dma" for internal use to simplify dma related code - added module `dma` -- added feature gate to select "with-dma" - module `gpio` has the following new types and traits: * Struct `PartiallyErasedPin` and `ErasedPin` replaces previous `Pin` * Struct `DynamicPin` allows pin to swap between an `Input` and `Output` pin during runtime at the cost of possible runtime errors * Trait `ExtiPin` allows connecting a pin to EXTI lines for interrupt and event handling - * Trait `Debugger` marks pins that upon bootup are dedicated to the DBG peripheral, must be `activate` before use as a gpio + * Struct `Debugger` marks pins that upon bootup are dedicated to the DBG peripheral, must be `activate` before use as a gpio * Trait `PinExt` adds functions to retrieve pin number and port id ('A', 'B', etc) - gpio Pins can be temporarily mode changed to do an action, using these methods: * `as_push_pull_output` @@ -42,9 +44,11 @@ This version depends on py32-rs v1.1.2 or later * Works with both 8 and 16 bit words, though 16bit not tested * Added `SpiSlave` for slave functionality, though it is not tested * Added frame size conversion methods, [ex: `frame_size_8_bit`] +- Checking that only one device has been selected in build.rs ### Changed +- Fixed repo url's - Changed all examples to use new api's where necessary - module `adc` changed to use new rcc enable, reset, and bus frequencies - module `gpio` @@ -76,11 +80,11 @@ This version depends on py32-rs v1.1.2 or later ### Security -## v0.1.1 +## v0.1.1 - 2024-10-10 -## V0.1.0 +## V0.1.0 - 2024-09-07 -## v0.0.1 +## v0.0.1 - 2023-06-10 - Original Release diff --git a/Cargo.toml b/Cargo.toml index aac4ce7..907e6b6 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -2,17 +2,16 @@ name = "py32f0xx-hal" version = "0.2.0" authors = [ - "Daniel Egger ", - "Thomas Bytheway ", - "Jesse Braham ", + "creatoy@yeah.net", + "Greg Green ", ] -edition = "2018" +edition = "2021" rust-version = "1.59" keywords = ["arm", "cortex-m", "py32f0xx", "hal"] license = "0BSD" readme = "README.md" -repository = "https://github.com/creatoy/py32f0xx-hal" +repository = "https://github.com/py32-rust/py32f0xx-hal" categories = ["embedded", "hardware-support", "no-std"] description = "Peripheral access API for py32F0 series microcontrollers" documentation = "https://docs.rs/crate/py32f0xx-hal" @@ -25,8 +24,12 @@ targets = ["thumbv6m-none-eabi"] bare-metal = { version = "1.0.0" } cast = "0.3.0" cortex-m = { version = "0.7.7", features = ["critical-section-single-core"] } -embedded-time = "0.12.1" +py32f0 = "0.2.0" +embedded-hal = "1.0" +embedded-hal-nb = "1.0" embedded-dma = "0.2.0" +embedded-io = "0.6.1" +embedded-time = "0.12.1" nb = "1.1.0" void = { version = "1.0.2", default-features = false } defmt = { version = "0.3.8", optional = true } @@ -40,20 +43,6 @@ package = "embedded-hal" version = "0.2.7" features = ["unproven"] -[dependencies.embedded-hal] -version = "1.0" - -[dependencies.embedded-hal-nb] -version = "1.0" - -[dependencies.embedded-io] -version = "0.6.1" - -[dependencies.py32f0] -version = "0.1.1" -features = [] -path = "../py32-rs/py32f0" - [dev-dependencies] cortex-m-rt = "0.7.3" panic-halt = "0.2.0" diff --git a/README.md b/README.md index d8a38d3..42082f0 100644 --- a/README.md +++ b/README.md @@ -1,28 +1,26 @@ py32f0xx-hal ============= -> This repo is modified from [stm32f0xx-hal](https://github.com/stm32-rs/stm32f0xx-hal) - > **NOTE: The function is not fully tested, and you are responsible for any problems with the use of this repository.** Known issue: - I2C not work -[![Continuous integration](https://github.com/creatoy/py32f0xx-hal/workflows/Continuous%20integration/badge.svg)](https://github.com/creatoy/py32f0xx-hal) +[![Continuous integration](https://github.com/creatoy/py32f0xx-hal/workflows/Continuous%20integration/badge.svg)](https://github.com/py32-rust/py32f0xx-hal) [![Crates.io](https://img.shields.io/crates/v/py32f0xx-hal.svg)](https://crates.io/crates/py32f0xx-hal) [![docs.rs](https://docs.rs/py32f0xx-hal/badge.svg)](https://docs.rs/py32f0xx-hal/) -[_py32f0xx-hal_](https://github.com/creatoy/py32f0xx-hal) contains a hardware abstraction on top of the peripheral access API for the puyasemi PY32F0xx family of microcontrollers. +[_py32f0xx-hal_](https://github.com/py32-rust/py32f0xx-hal) contains a hardware abstraction on top of the peripheral access API for the puyasemi PY32F0xx family of microcontrollers. Collaboration on this crate is highly welcome, as are pull requests! Supported ------------------------ -* __py32f030__ (py32f030xx4, py32f030xx6, py32f030xx7, py32f030xx8) -* __py32f003__ (py32f003xx4, py32f003xx6, py32f030xx8) -* __py32f002a__ (py32f002ax5) -* __py32f002b__ (py32f002bx5) +* __py32f030__ (py32f030xx4, py32f030xx6, py32f030xx7, py32f030xx8) +* __py32f003__ (py32f003xx4, py32f003xx6, py32f030xx8) +* __py32f002a__ (py32f002ax5) +* __py32f002b__ (py32f002bx5) Getting Started --------------- @@ -36,14 +34,14 @@ To use py32f0xx-hal as a dependency in a standalone project the target device fe [dependencies] cortex-m = "0.7.7" cortex-m-rt = "0.7.3" -py32f0xx-hal = { version = "0.1.0", features = ["py32f002ax5"]} +py32f0xx-hal = { version = "0.2.0", features = ["py32f002ax5"]} ``` If you are unfamiliar with embedded development using Rust, there are a number of fantastic resources available to help. -- [Embedded Rust Documentation](https://docs.rust-embedded.org/) -- [The Embedded Rust Book](https://docs.rust-embedded.org/book/) -- [Rust Embedded FAQ](https://docs.rust-embedded.org/faq.html) +- [Embedded Rust Documentation](https://docs.rust-embedded.org/) +- [The Embedded Rust Book](https://docs.rust-embedded.org/book/) +- [Rust Embedded FAQ](https://docs.rust-embedded.org/faq.html) - [rust-embedded/awesome-embedded-rust](https://github.com/rust-embedded/awesome-embedded-rust) @@ -58,6 +56,11 @@ Changelog See [CHANGELOG.md](CHANGELOG.md). +Credits +------- + +> This repo was inspired by [stm32f0xx-hal](https://github.com/stm32-rs/stm32f0xx-hal) and [stm32f1xx-hal](https://github.com/stm32-rs/stm32f1xx-hal) + License ------- diff --git a/build.rs b/build.rs new file mode 100644 index 0000000..5e4168e --- /dev/null +++ b/build.rs @@ -0,0 +1,36 @@ +use std::env; + +#[derive(Clone, Copy, Debug)] +enum GetOneError { + None, + Multiple, +} + +trait IteratorExt: Iterator { + fn get_one(self) -> Result; +} + +impl IteratorExt for T { + fn get_one(mut self) -> Result { + match (self.next(), self.next()) { + (Some(res), None) => Ok(res), + (None, _) => Err(GetOneError::None), + _ => Err(GetOneError::Multiple), + } + } +} + +fn main() { + let _chip_name = match env::vars() + .map(|(a, _)| a) + .filter(|x| x.starts_with("CARGO_FEATURE_PY32F0")) + .get_one() + { + Ok(x) => x, + Err(GetOneError::None) => panic!("No py32f0xx Cargo feature enabled"), + Err(GetOneError::Multiple) => panic!("Multiple py32f0xx Cargo features enabled"), + } + .strip_prefix("CARGO_FEATURE_") + .unwrap() + .to_ascii_lowercase(); +} diff --git a/src/rcc.rs b/src/rcc.rs index 9c75f80..a120895 100644 --- a/src/rcc.rs +++ b/src/rcc.rs @@ -84,7 +84,7 @@ pub enum MCOSrc { NoClock = 0, ///1: SYSCLK clock selected Sysclk = 1, - ///3: MSI oscillator clock selected + ///3: HSI oscillator clock selected Hsi = 3, ///4: HSE oscillator clock selected Hse = 4, diff --git a/src/timer.rs b/src/timer.rs index 8c22e99..404b5b0 100644 --- a/src/timer.rs +++ b/src/timer.rs @@ -508,7 +508,7 @@ impl FTimer { self.tim.clear_interrupt_flag(event); } - pub fn get_interrupt(&mut self) -> Event { + pub fn get_interrupt(&self) -> Event { self.tim.get_interrupt_flag() } From b2a83e38122ae382b7384297518a1750f69ae38a Mon Sep 17 00:00:00 2001 From: Greg Green Date: Mon, 30 Dec 2024 09:45:39 -0800 Subject: [PATCH 09/11] Fixed rtc,timer,pwm after all feature compile check Fixed chip feature in tools/capture* scripts Fixed tools/check.py Updated README.md Deleted build.rs as it doesn't work with current features Fixed github actions that didn't work --- .github/workflows/changelog.yml | 4 +-- .github/workflows/ci.yml | 10 ++++--- CHANGELOG.md | 7 +++-- README.md | 17 +++++++++--- build.rs | 36 -------------------------- src/lib.rs | 2 +- src/pwm.rs | 2 +- src/rcc/enable.rs | 3 ++- src/rtc.rs | 11 +++++--- src/timer.rs | 7 ++++- src/timer/monotonic.rs | 2 +- tools/capture_example_bloat.sh | 2 +- tools/capture_nightly_example_bloat.sh | 2 +- tools/check.py | 15 +++++++---- 14 files changed, 55 insertions(+), 65 deletions(-) delete mode 100644 build.rs diff --git a/.github/workflows/changelog.yml b/.github/workflows/changelog.yml index 0f68bbf..c0d72f3 100644 --- a/.github/workflows/changelog.yml +++ b/.github/workflows/changelog.yml @@ -9,10 +9,10 @@ jobs: runs-on: ubuntu-latest steps: - name: Checkout sources - uses: actions/checkout@v2 + uses: actions/checkout@v3 - name: Changelog updated - uses: Zomzog/changelog-checker@v1.1.0 + uses: Zomzog/changelog-checker@v1.2.0 with: fileName: CHANGELOG.md env: diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index f041214..cc9fb82 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -2,6 +2,7 @@ on: push: branches: [ staging, trying, master ] pull_request: + merge_group: name: Continuous integration @@ -17,14 +18,17 @@ jobs: experimental: true steps: - - uses: actions/checkout@v2 - - uses: actions-rs/toolchain@v1 + - name: Checkout code + uses: actions/checkout@v3 + + - name: Install Rust + uses: actions-rs/toolchain@v1 with: profile: minimal toolchain: ${{ matrix.rust }} target: thumbv6m-none-eabi override: true - + - name: Regular build run: python tools/check.py diff --git a/CHANGELOG.md b/CHANGELOG.md index 4249abf..bf306d7 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -44,7 +44,6 @@ This version depends on py32-rs v0.2.0 or later * Works with both 8 and 16 bit words, though 16bit not tested * Added `SpiSlave` for slave functionality, though it is not tested * Added frame size conversion methods, [ex: `frame_size_8_bit`] -- Checking that only one device has been selected in build.rs ### Changed @@ -69,8 +68,6 @@ This version depends on py32-rs v0.2.0 or later - module `timers` * changed to use rcc enable, reset, and bus frequencies -### Deprecated - ### Removed - `delay` and `timers` modules removed, the functionality is in the `timer` module now @@ -78,7 +75,9 @@ This version depends on py32-rs v0.2.0 or later ### Fixed -### Security +- Fixed github action `changelog.yml` +- Fixed github action `ci.yml` +- Fixed `tool/check.py` ## v0.1.1 - 2024-10-10 diff --git a/README.md b/README.md index 42082f0..9e3542a 100644 --- a/README.md +++ b/README.md @@ -1,14 +1,19 @@ py32f0xx-hal ============= -> **NOTE: The function is not fully tested, and you are responsible for any problems with the use of this repository.** +> [HAL] for the py32f0xx family of microcontrollers -Known issue: - - I2C not work +> **NOTE: The function's are not fully tested, and you are responsible for any problems with the use of this repository.** -[![Continuous integration](https://github.com/creatoy/py32f0xx-hal/workflows/Continuous%20integration/badge.svg)](https://github.com/py32-rust/py32f0xx-hal) +Known issues: + - I2C master/slave not tested + - rtc not tested + +[![Crates.io](https://img.shields.io/crates/d/py32f0xx-hal.svg)](https://crates.io/crates/py32f0xx-hal) [![Crates.io](https://img.shields.io/crates/v/py32f0xx-hal.svg)](https://crates.io/crates/py32f0xx-hal) [![docs.rs](https://docs.rs/py32f0xx-hal/badge.svg)](https://docs.rs/py32f0xx-hal/) +[![dependency status](https://deps.rs/repo/github/[py32-rust/py32f0xx-hal/status.svg)](https://deps.rs/repo/github/py32-rust/py32f0xx-hal) +[![Continuous integration](https://github.com/creatoy/py32f0xx-hal/workflows/Continuous%20integration/badge.svg)](https://github.com/py32-rust/py32f0xx-hal) [_py32f0xx-hal_](https://github.com/py32-rust/py32f0xx-hal) contains a hardware abstraction on top of the peripheral access API for the puyasemi PY32F0xx family of microcontrollers. @@ -32,8 +37,12 @@ $ cargo build --features=py32f002ax5 --example=blinky To use py32f0xx-hal as a dependency in a standalone project the target device feature must be specified in the `Cargo.toml` file: ``` [dependencies] +embedded-hal = "1" +nb = "1" cortex-m = "0.7.7" cortex-m-rt = "0.7.3" +# Panic behaviour, see https://crates.io/keywords/panic-impl for alternatives +panic-halt = "0.2.0" py32f0xx-hal = { version = "0.2.0", features = ["py32f002ax5"]} ``` diff --git a/build.rs b/build.rs deleted file mode 100644 index 5e4168e..0000000 --- a/build.rs +++ /dev/null @@ -1,36 +0,0 @@ -use std::env; - -#[derive(Clone, Copy, Debug)] -enum GetOneError { - None, - Multiple, -} - -trait IteratorExt: Iterator { - fn get_one(self) -> Result; -} - -impl IteratorExt for T { - fn get_one(mut self) -> Result { - match (self.next(), self.next()) { - (Some(res), None) => Ok(res), - (None, _) => Err(GetOneError::None), - _ => Err(GetOneError::Multiple), - } - } -} - -fn main() { - let _chip_name = match env::vars() - .map(|(a, _)| a) - .filter(|x| x.starts_with("CARGO_FEATURE_PY32F0")) - .get_one() - { - Ok(x) => x, - Err(GetOneError::None) => panic!("No py32f0xx Cargo feature enabled"), - Err(GetOneError::Multiple) => panic!("Multiple py32f0xx Cargo features enabled"), - } - .strip_prefix("CARGO_FEATURE_") - .unwrap() - .to_ascii_lowercase(); -} diff --git a/src/lib.rs b/src/lib.rs index 24eccce..b516a4a 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -27,7 +27,7 @@ pub mod prelude; pub mod pwm; #[cfg(feature = "device-selected")] pub mod rcc; -#[cfg(feature = "device-selected")] +#[cfg(any(feature = "py32f003", feature = "py32f030"))] pub mod rtc; #[cfg(feature = "device-selected")] pub mod serial; diff --git a/src/pwm.rs b/src/pwm.rs index 728fe41..4a26f2b 100644 --- a/src/pwm.rs +++ b/src/pwm.rs @@ -698,7 +698,7 @@ macro_rules! pwm_1_channel { $TIMX::reset(rcc); if PINS::C1 { - tim.ccmr1_output().modify(|_, w| w.oc1pe().set_bit().oc1m().bits(6)); + tim.ccmr1_output().modify(|_, w| unsafe { w.oc1pe().set_bit().oc1m().bits(6) }); } let ticks = $TIMX::timer_clock(clocks).raw() / freq.into().raw(); diff --git a/src/rcc/enable.rs b/src/rcc/enable.rs index 249a33a..1fb9677 100644 --- a/src/rcc/enable.rs +++ b/src/rcc/enable.rs @@ -42,7 +42,6 @@ bus! { GPIOA => (APB, iopenr, ioprstr, 0), GPIOB => (APB, iopenr, ioprstr, 1), I2C => (APB, apbenr1, apbrstr1, 21), - LPTIM => (APB, apbenr1, apbrstr1, 31), PWR => (APB, apbenr1, apbrstr1, 28), SPI1 => (APB, apbenr2, apbrstr2, 12), SYSCFG => (APB, apbenr2, apbrstr2, 0), @@ -65,11 +64,13 @@ bus! { #[cfg(any(feature = "py32f002a", feature = "py32f003", feature = "py32f030"))] bus! { GPIOF => (APB, iopenr, ioprstr, 5), + LPTIM => (APB, apbenr1, apbrstr1, 31), } #[cfg(any(feature = "py32f002b"))] bus! { GPIOC => (APB, iopenr, ioprstr, 2), + LPTIM1 => (APB, apbenr1, apbrstr1, 31), } #[cfg(any(feature = "py32f030"))] diff --git a/src/rtc.rs b/src/rtc.rs index 8d3803a..d3b96d3 100644 --- a/src/rtc.rs +++ b/src/rtc.rs @@ -9,12 +9,14 @@ use core::convert::Infallible; use core::marker::PhantomData; // The LSE runs at at 32 768 hertz unless an external clock is provided +#[cfg(feature = "py32f030")] const LSE_HERTZ: Hertz = Hz(32_768); const LSI_HERTZ: Hertz = Hz(32_768); /// RTC clock source HSE clock divided by 128 (type state) pub struct RtcClkHseDiv128; /// RTC clock source LSE oscillator clock (type state) +#[cfg(feature = "py32f030")] pub struct RtcClkLse; /// RTC clock source LSI oscillator clock (type state) pub struct RtcClkLsi; @@ -41,11 +43,12 @@ CPU when it is in low power mode. [examples/blinky_rtc.rs]: https://github.com/py32f0xx-hal/blob/v0.2.0/examples/blinky_rtc.rs */ -pub struct Rtc { +pub struct Rtc { regs: RTC, _clock_source: PhantomData, } +#[cfg(feature = "py32f030")] impl Rtc { /** Initialises the RTC with low-speed external crystal source (lse). @@ -260,13 +263,13 @@ impl Rtc { impl Rtc { /// Selects the frequency of the RTC Timer - /// NOTE: Maximum frequency of 16384 Hz using the internal LSE + /// NOTE: Maximum frequency of 16384 Hz using the internal LSI pub fn select_frequency(&mut self, frequency: Hertz) { // The manual says that the zero value for the prescaler is not recommended, thus the // minimum division factor is 2 (prescaler + 1) - assert!(frequency <= LSE_HERTZ / 2); + assert!(frequency <= LSI_HERTZ / 2); - let prescaler = LSE_HERTZ.raw() / frequency.raw() - 1; + let prescaler = LSI_HERTZ.raw() / frequency.raw() - 1; self.perform_write(|s| { s.regs.prlh.write(|w| unsafe { w.bits(prescaler >> 16) }); s.regs diff --git a/src/timer.rs b/src/timer.rs index 404b5b0..a8cbbce 100644 --- a/src/timer.rs +++ b/src/timer.rs @@ -559,7 +559,12 @@ hal!( pac::TIM16: [Timer16, u16, apb_fz2, dbg_timer16_stop, opm: opm,], ); -#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002b"))] +#[cfg(any(feature = "py32f030", feature = "py32f003"))] hal!( pac::TIM14: [Timer14, u16, apb_fz2, dbg_timer14_stop,], ); + +#[cfg(feature = "py32f002b")] +hal!( + pac::TIM14: [Timer14, u16, apb_fz2, dbg_tim14_stop,], +); diff --git a/src/timer/monotonic.rs b/src/timer/monotonic.rs index a940aed..bc8459a 100644 --- a/src/timer/monotonic.rs +++ b/src/timer/monotonic.rs @@ -146,7 +146,7 @@ mono!(crate::pac::TIM3); #[cfg(any(feature = "py32f030", feature = "py32f003"))] mono!(crate::pac::TIM17); -#[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002a"))] +#[cfg(any(feature = "py32f030", feature = "py32f003"))] mono!(crate::pac::TIM16); #[cfg(any(feature = "py32f030", feature = "py32f003", feature = "py32f002b"))] diff --git a/tools/capture_example_bloat.sh b/tools/capture_example_bloat.sh index 084aaca..1ad0906 100755 --- a/tools/capture_example_bloat.sh +++ b/tools/capture_example_bloat.sh @@ -1,7 +1,7 @@ #!/bin/bash version="stable" -features="py32f042,rt" +features="py32f030,rt" filename="bloat_log_"$version"_"`date -Iminutes`".txt" filenamenoopt="bloat_noopt_log_"$version"_"`date -Iminutes`".txt" diff --git a/tools/capture_nightly_example_bloat.sh b/tools/capture_nightly_example_bloat.sh index 4191651..705fd83 100755 --- a/tools/capture_nightly_example_bloat.sh +++ b/tools/capture_nightly_example_bloat.sh @@ -1,7 +1,7 @@ #!/bin/bash version="nightly" -features="py32f042,rt" +features="py32f030,rt" filename="bloat_log_"$version"_"`date -Iminutes`".txt" filenamenoopt="bloat_noopt_log_"$version"_"`date -Iminutes`".txt" diff --git a/tools/check.py b/tools/check.py index 8d184f5..0d63581 100755 --- a/tools/check.py +++ b/tools/check.py @@ -16,7 +16,7 @@ def run(mcu, cargo_cmd): if mcu == "": return run_inner(cargo_cmd) else: - return run_inner(cargo_cmd + ["--examples", "--features={}".format(mcu)]) + return run_inner(cargo_cmd + ["--features={}".format(mcu)]) def main(): @@ -27,14 +27,20 @@ def main(): ) crate_info = cargo_meta["packages"][0] - features = [ - "{},rt,py32-usbd".format(x) + "{},defmt,rt,rtic".format(x) for x in crate_info["features"].keys() if x != "device-selected" and x != "rt" + and x != "rtic" + and x != "defmt" + and x != "with-dma" and x != "py32f030" - and x != "py32-usbd" + and x != "py32f003" + and x != "py32f002a" + and x != "py32f002b" + and not x.startswith("flash") + and not x.startswith("ram") ] if 'size_check' in sys.argv: @@ -49,4 +55,3 @@ def main(): if __name__ == "__main__": main() - From f8e2370ec3ff05b2054638cb552b3a65c5b29942 Mon Sep 17 00:00:00 2001 From: Greg Green Date: Tue, 21 Jan 2025 17:10:16 -0800 Subject: [PATCH 10/11] Removed SYST clock divide by 8 Set SYST clock source to sysclk for configure function Fixed Clocks.sysclk initialization Adjusted all examples to remove if let, and loop construct, the compiler was optimizing out a lot of the example functionality due to that code construction --- Cargo.toml | 1 - examples/adc_values.rs | 76 +++++++++----------- examples/blinky.rs | 34 ++++----- examples/blinky_adc.rs | 48 ++++++------- examples/blinky_delay.rs | 24 +++---- examples/blinky_multiple.rs | 54 +++++++------- examples/blinky_timer.rs | 30 ++++---- examples/blinky_timer_irq.rs | 79 ++++++++++----------- examples/exti.rs | 3 +- examples/flash_systick.rs | 46 ++++++------ examples/flash_systick_fancier.rs | 48 ++++++------- examples/i2c_find_address.rs | 61 ++++++++-------- examples/led_hal_button_irq.rs | 113 ++++++++++++++---------------- examples/pwm.rs | 35 +++++---- examples/pwm_complementary.rs | 69 ++++++++---------- examples/serial_echo.rs | 54 +++++++------- examples/serial_spi_bridge.rs | 58 +++++++-------- examples/serial_stopwatch.rs | 103 +++++++++++++-------------- examples/spi_hal_apa102c.rs | 77 ++++++++++---------- examples/spi_rc522.rs | 110 ++++++++++++++--------------- examples/watchdog.rs | 62 ++++++++-------- src/rcc.rs | 2 +- src/timer.rs | 10 +-- 23 files changed, 560 insertions(+), 637 deletions(-) diff --git a/Cargo.toml b/Cargo.toml index 907e6b6..7ddfd1a 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -6,7 +6,6 @@ authors = [ "Greg Green ", ] edition = "2021" -rust-version = "1.59" keywords = ["arm", "cortex-m", "py32f0xx", "hal"] license = "0BSD" diff --git a/examples/adc_values.rs b/examples/adc_values.rs index 239a4b3..ad851f4 100644 --- a/examples/adc_values.rs +++ b/examples/adc_values.rs @@ -25,60 +25,54 @@ static SHARED: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { - if let (Some(dp), Some(cp)) = ( - hal::pac::Peripherals::take(), - cortex_m::peripheral::Peripherals::take(), - ) { - cortex_m::interrupt::free(move |cs| { - let mut flash = dp.FLASH; - let rcc = dp.RCC.configure().sysclk(24.MHz()).freeze(&mut flash); + let dp = hal::pac::Peripherals::take().unwrap(); + let cp = cortex_m::peripheral::Peripherals::take().unwrap(); + cortex_m::interrupt::free(move |cs| { + let mut flash = dp.FLASH; + let rcc = dp.RCC.configure().sysclk(24.MHz()).freeze(&mut flash); - let gpioa = dp.GPIOA.split(); + let gpioa = dp.GPIOA.split(); - let mut syst = cp.SYST; + let mut syst = cp.SYST; - // Set source for SysTick counter, here full operating frequency (== 24MHz) - syst.set_clock_source(Core); + // Set source for SysTick counter, here full operating frequency (== 24MHz) + syst.set_clock_source(Core); - // Set reload value, i.e. timer delay 24 MHz/counts - syst.set_reload(24_000_000 - 1); + // Set reload value, i.e. timer delay 24 MHz/counts + syst.set_reload(24_000_000 - 1); - // Start SysTick counter - syst.enable_counter(); + // Start SysTick counter + syst.enable_counter(); - // Start SysTick interrupt generation - syst.enable_interrupt(); + // Start SysTick interrupt generation + syst.enable_interrupt(); - // USART1 at PA2 (TX) and PA3(RX) - let tx = gpioa.pa2.into_alternate_af1(); - let _rx = gpioa.pa3.into_alternate_af1(); // don't need, can be removed + // USART1 at PA2 (TX) and PA3(RX) + let tx = gpioa.pa2.into_alternate_af1(); + let _rx = gpioa.pa3.into_alternate_af1(); // don't need, can be removed - // Initialiase UART for transmission only - let mut tx = dp.USART1.tx(tx, 115_200.bps(), &rcc.clocks); + // Initialise UART for transmission only + let mut tx = dp.USART1.tx(tx, 115_200.bps(), &rcc.clocks); - // Initialise ADC - let adc = hal::adc::Adc::new(dp.ADC, hal::adc::AdcClockMode::default()); + // Initialise ADC + let adc = hal::adc::Adc::new(dp.ADC, hal::adc::AdcClockMode::default()); - let ain0 = gpioa.pa0.into_analog(); // ADC_IN0 - let ain1 = gpioa.pa1.into_analog(); // ADC_IN1 + let ain0 = gpioa.pa0.into_analog(); // ADC_IN0 + let ain1 = gpioa.pa1.into_analog(); // ADC_IN1 - // Output a friendly greeting - tx.write_str("\n\rThis ADC example will read various values using the ADC and print them out to the serial terminal\r\n").ok(); - info!("\n\rThis ADC example will read various values using the ADC and print them out to the serial terminal\r\n"); + // Output a friendly greeting + tx.write_str("\n\rThis ADC example will read various values using the ADC and print them out to the serial terminal\r\n").ok(); + info!("\n\rThis ADC example will read various values using the ADC and print them out to the serial terminal\r\n"); - // Move all components under Mutex supervision - *SHARED.borrow(cs).borrow_mut() = Some(Shared { - adc, - tx, - ain0, - ain1, - }); + // Move all components under Mutex supervision + *SHARED.borrow(cs).borrow_mut() = Some(Shared { + adc, + tx, + ain0, + ain1, }); - } - - loop { - continue; - } + }); + loop {} } #[exception] diff --git a/examples/blinky.rs b/examples/blinky.rs index 20b1df0..73b47f8 100644 --- a/examples/blinky.rs +++ b/examples/blinky.rs @@ -11,27 +11,21 @@ use cortex_m_rt::entry; #[entry] fn main() -> ! { - if let Some(mut p) = pac::Peripherals::take() { - let _rcc = p.RCC.configure().sysclk(8.MHz()).freeze(&mut p.FLASH); - - let gpioa = p.GPIOA.split(); - - // (Re-)configure PA5 as output - let mut led = gpioa.pa5.into_push_pull_output(); - - loop { - // Turn PA5 on a million times in a row - for _ in 0..1_000_000 { - led.set_high(); - } - // Then turn PA5 off a million times in a row - for _ in 0..1_000_000 { - led.set_low(); - } - } - } + let p = pac::Peripherals::take().unwrap(); + + let gpioa = p.GPIOA.split(); + + // (Re-)configure PA5 as output + let mut led = gpioa.pa5.into_push_pull_output(); loop { - continue; + // Turn PA5 on a million times in a row + for _ in 0..1_000_000 { + led.set_high(); + } + // Then turn PA5 off a million times in a row + for _ in 0..1_000_000 { + led.set_low(); + } } } diff --git a/examples/blinky_adc.rs b/examples/blinky_adc.rs index 4b3329f..62b4bba 100644 --- a/examples/blinky_adc.rs +++ b/examples/blinky_adc.rs @@ -14,38 +14,34 @@ use embedded_hal_02::blocking::delay::DelayMs; #[entry] fn main() -> ! { - if let (Some(mut p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { - let rcc = p.RCC.configure().sysclk(8.MHz()).freeze(&mut p.FLASH); + let mut p = pac::Peripherals::take().unwrap(); + let cp = Peripherals::take().unwrap(); + let rcc = p.RCC.configure().freeze(&mut p.FLASH); - let gpioa = p.GPIOA.split(); + let gpioa = p.GPIOA.split(); - // (Re-)configure PA5 as output - let mut led = gpioa.pa5.into_push_pull_output(); - // (Re-)configure PA0 as analog input - let mut an_in = gpioa.pa0.into_analog(); + // (Re-)configure PA5 as output + let mut led = gpioa.pa5.into_push_pull_output(); + // (Re-)configure PA0 as analog input + let mut an_in = gpioa.pa0.into_analog(); - // Get delay provider - let mut delay = cp.SYST.delay(&rcc.clocks); + // Get delay provider + let mut delay = cp.SYST.delay(&rcc.clocks); - // Get access to the ADC - let mut adc = Adc::new(p.ADC, hal::adc::AdcClockMode::Pclk); + // Get access to the ADC + let mut adc = Adc::new(p.ADC, hal::adc::AdcClockMode::Pclk); - loop { - led.toggle(); - - let time: u16 = if let Ok(val) = adc.read(&mut an_in) as Result { - /* shift the value right by 3, same as divide by 8, reduces - the 0-4095 range into something approximating 1-512 */ - (val >> 3) + 1 - } else { - 1000 - }; + loop { + led.toggle(); - delay.delay_ms(time); - } - } + let time: u16 = if let Ok(val) = adc.read(&mut an_in) as Result { + /* shift the value right by 3, same as divide by 8, reduces + the 0-4095 range into something approximating 1-512 */ + (val >> 3) + 1 + } else { + 1000 + }; - loop { - continue; + delay.delay_ms(time); } } diff --git a/examples/blinky_delay.rs b/examples/blinky_delay.rs index 5825325..66f33c9 100644 --- a/examples/blinky_delay.rs +++ b/examples/blinky_delay.rs @@ -12,24 +12,20 @@ use embedded_hal_02::blocking::delay::DelayMs; #[entry] fn main() -> ! { - if let (Some(mut p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { - let rcc = p.RCC.configure().sysclk(8.MHz()).freeze(&mut p.FLASH); + let mut p = pac::Peripherals::take().unwrap(); + let cp = Peripherals::take().unwrap(); + let rcc = p.RCC.configure().freeze(&mut p.FLASH); - let gpioa = p.GPIOA.split(); + let gpioa = p.GPIOA.split(); - // (Re-)configure PA5 as output - let mut led = gpioa.pa5.into_push_pull_output(); + // (Re-)configure PA5 as output + let mut led = gpioa.pa5.into_push_pull_output(); - // Get delay provider - let mut delay = cp.SYST.delay(&rcc.clocks); - - loop { - led.toggle(); - delay.delay_ms(1_000_u16); - } - } + // Get delay provider + let mut delay = cp.SYST.delay(&rcc.clocks); loop { - continue; + led.toggle(); + delay.delay_ms(1_000_u16); } } diff --git a/examples/blinky_multiple.rs b/examples/blinky_multiple.rs index f19f983..f6b32ee 100644 --- a/examples/blinky_multiple.rs +++ b/examples/blinky_multiple.rs @@ -13,36 +13,32 @@ use embedded_hal_02::blocking::delay::DelayMs; #[entry] fn main() -> ! { - if let (Some(mut p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { - let rcc = p.RCC.configure().sysclk(8.MHz()).freeze(&mut p.FLASH); - - let gpioa = p.GPIOA.split(); - let gpiob = p.GPIOB.split(); - - // (Re-)configure PA5 as output - let led1 = gpioa.pa5.into_push_pull_output(); - // (Re-)configure PB1 as output - let led2 = gpiob.pb1.into_push_pull_output(); - - // Get delay provider - let mut delay = cp.SYST.delay(&rcc.clocks); - - // Store them together after erasing the type - let mut leds = [led1.erase(), led2.erase()]; - loop { - for l in &mut leds { - l.set_high(); - } - delay.delay_ms(1_000_u16); - - for l in &mut leds { - l.set_low(); - } - delay.delay_ms(1_000_u16); - } - } + let mut p = pac::Peripherals::take().unwrap(); + let cp = Peripherals::take().unwrap(); + let rcc = p.RCC.configure().freeze(&mut p.FLASH); + + let gpioa = p.GPIOA.split(); + let gpiob = p.GPIOB.split(); + + // (Re-)configure PA5 as output + let led1 = gpioa.pa5.into_push_pull_output(); + // (Re-)configure PB1 as output + let led2 = gpiob.pb1.into_push_pull_output(); + // Get delay provider + let mut delay = cp.SYST.delay(&rcc.clocks); + + // Store them together after erasing the type + let mut leds = [led1.erase(), led2.erase()]; loop { - continue; + for l in &mut leds { + l.set_high(); + } + delay.delay_ms(1_000_u16); + + for l in &mut leds { + l.set_low(); + } + delay.delay_ms(1_000_u16); } } diff --git a/examples/blinky_timer.rs b/examples/blinky_timer.rs index 2d3d48e..e72c5d0 100644 --- a/examples/blinky_timer.rs +++ b/examples/blinky_timer.rs @@ -6,31 +6,27 @@ use panic_halt as _; use py32f0xx_hal as hal; use crate::hal::{pac, prelude::*}; + use cortex_m_rt::entry; #[entry] fn main() -> ! { - if let Some(mut p) = pac::Peripherals::take() { - let rcc = p.RCC.configure().sysclk(8.MHz()).freeze(&mut p.FLASH); - - let gpioa = p.GPIOA.split(); + let mut p = pac::Peripherals::take().unwrap(); + let rcc = p.RCC.configure().freeze(&mut p.FLASH); - // (Re-)configure PA5 as output - let mut led = gpioa.pa5.into_push_pull_output(); + let gpioa = p.GPIOA.split(); - // Set up a timer expiring after 200ms - let mut timer = p.TIM1.counter_hz(&rcc.clocks); - timer.start(5.Hz()).unwrap(); + // (Re-)configure PA5 as output + let mut led = gpioa.pa5.into_push_pull_output(); - loop { - led.toggle(); - - // Wait for the timer to expire - nb::block!(timer.wait()).ok(); - } - } + // Set up a timer expiring after 200ms + let mut timer = p.TIM1.counter_hz(&rcc.clocks); + timer.start(5.Hz()).unwrap(); loop { - continue; + led.toggle(); + + // Wait for the timer to expire + nb::block!(timer.wait()).ok(); } } diff --git a/examples/blinky_timer_irq.rs b/examples/blinky_timer_irq.rs index f18c7b6..f9d7bd7 100644 --- a/examples/blinky_timer_irq.rs +++ b/examples/blinky_timer_irq.rs @@ -41,7 +41,7 @@ fn TIM16() { let int = INT.get_or_insert_with(|| { cortex_m::interrupt::free(|cs| { - // Move timer here, leaving a None in its place + // Move LED pin here, leaving a None in its place GINT.borrow(cs).replace(None).unwrap() }) }); @@ -52,44 +52,41 @@ fn TIM16() { #[entry] fn main() -> ! { - if let (Some(mut p), Some(cp)) = (Peripherals::take(), c_m_Peripherals::take()) { - cortex_m::interrupt::free(move |cs| { - let rcc = p - .RCC - .configure() - .sysclk(24.MHz()) - .pclk(24.MHz()) - .freeze(&mut p.FLASH); - - let gpioa = p.GPIOA.split(); - - // (Re-)configure PA5 as output - let led = gpioa.pa5.into_push_pull_output(); - - // Move the pin into our global storage - *GLED.borrow(cs).borrow_mut() = Some(led); - - // Set up a timer expiring after 1s - let mut timer = p.TIM16.counter_hz(&rcc.clocks); - - // Generate an interrupt when the timer expires - timer.listen(Event::Update); - timer.start(1.Hz()).unwrap(); - - // Move the timer into our global storage - *GINT.borrow(cs).borrow_mut() = Some(timer); - - // Enable TIM16 IRQ, set prio 1 and clear any pending IRQs - let mut nvic = cp.NVIC; - unsafe { - nvic.set_priority(Interrupt::TIM16, 1); - cortex_m::peripheral::NVIC::unmask(Interrupt::TIM16); - } - cortex_m::peripheral::NVIC::unpend(Interrupt::TIM16); - }); - } - - loop { - continue; - } + let mut p = Peripherals::take().unwrap(); + let cp = c_m_Peripherals::take().unwrap(); + cortex_m::interrupt::free(move |cs| { + let rcc = p + .RCC + .configure() + .sysclk(24.MHz()) + .pclk(24.MHz()) + .freeze(&mut p.FLASH); + + let gpioa = p.GPIOA.split(); + + // (Re-)configure PA5 as output + let led = gpioa.pa5.into_push_pull_output(); + + // Move the pin into our global storage + *GLED.borrow(cs).borrow_mut() = Some(led); + + // Set up a timer expiring after 1s + let mut timer = p.TIM16.counter_hz(&rcc.clocks); + + // Generate an interrupt when the timer expires + timer.listen(Event::Update); + timer.start(1.Hz()).unwrap(); + + // Move the timer into our global storage + *GINT.borrow(cs).borrow_mut() = Some(timer); + + // Enable TIM16 IRQ, set prio 1 and clear any pending IRQs + let mut nvic = cp.NVIC; + unsafe { + nvic.set_priority(Interrupt::TIM16, 1); + cortex_m::peripheral::NVIC::unmask(Interrupt::TIM16); + } + cortex_m::peripheral::NVIC::unpend(Interrupt::TIM16); + }); + loop {} } diff --git a/examples/exti.rs b/examples/exti.rs index a1dfa3a..752fdfb 100644 --- a/examples/exti.rs +++ b/examples/exti.rs @@ -42,7 +42,7 @@ fn main() -> ! { // initialization phase let mut p = pac::Peripherals::take().unwrap(); let _cp = cortex_m::peripheral::Peripherals::take().unwrap(); - let _rcc = p.RCC.configure().sysclk(8.MHz()).freeze(&mut p.FLASH); + let _rcc = p.RCC.configure().freeze(&mut p.FLASH); { // the scope ensures that the int_pin reference is dropped before the first ISR can be executed. @@ -61,6 +61,7 @@ fn main() -> ! { unsafe { pac::NVIC::unmask(pac::Interrupt::EXTI4_15); } + cortex_m::peripheral::NVIC::unpend(pac::Interrupt::EXTI4_15); loop {} } diff --git a/examples/flash_systick.rs b/examples/flash_systick.rs index 56c0d3b..2300587 100644 --- a/examples/flash_systick.rs +++ b/examples/flash_systick.rs @@ -21,40 +21,38 @@ static GPIO: Mutex>>>> = Mutex::new(R #[entry] fn main() -> ! { - if let (Some(mut p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { - cortex_m::interrupt::free(move |cs| { - let _rcc = p.RCC.configure().sysclk(24.MHz()).freeze(&mut p.FLASH); + let mut p = pac::Peripherals::take().unwrap(); + let cp = Peripherals::take().unwrap(); + let _rcc = p.RCC.configure().sysclk(24.MHz()).freeze(&mut p.FLASH); - let gpioa = p.GPIOA.split(); + let gpioa = p.GPIOA.split(); - // (Re-)configure PA5 as output - let led = gpioa.pa5.into_push_pull_output(); + // (Re-)configure PA5 as output + let led = gpioa.pa5.into_push_pull_output(); - // Transfer GPIO into a shared structure - *GPIO.borrow(cs).borrow_mut() = Some(led); + cortex_m::interrupt::free(move |cs| { + // Transfer GPIO into a shared structure + *GPIO.borrow(cs).borrow_mut() = Some(led); + }); - let mut syst = cp.SYST; + let mut syst = cp.SYST; - // Initialise SysTick counter with a defined value - unsafe { syst.cvr.write(1) }; + // Initialise SysTick counter with a defined value + unsafe { syst.cvr.write(1) }; - // Set source for SysTick counter, here full operating frequency (== 48MHz) - syst.set_clock_source(Core); + // Set source for SysTick counter, here full operating frequency (== 48MHz) + syst.set_clock_source(Core); - // Set reload value, i.e. timer delay 24 MHz/2 Mcounts == 12Hz or 83ms - syst.set_reload(2_000_000 - 1); + // Set reload value, i.e. timer delay 24 MHz/2 Mcounts == 12Hz or 83ms + syst.set_reload(2_000_000 - 1); - // Start counting - syst.enable_counter(); + // Start counting + syst.enable_counter(); - // Enable interrupt generation - syst.enable_interrupt(); - }); - } + // Enable interrupt generation + syst.enable_interrupt(); - loop { - continue; - } + loop {} } // Define an exception handler, i.e. function to call when exception occurs. Here, if our SysTick diff --git a/examples/flash_systick_fancier.rs b/examples/flash_systick_fancier.rs index 1a5100b..dddebc5 100644 --- a/examples/flash_systick_fancier.rs +++ b/examples/flash_systick_fancier.rs @@ -21,41 +21,39 @@ static GPIO: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { - if let (Some(mut p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { - cortex_m::interrupt::free(move |cs| { - let _rcc = p.RCC.configure().sysclk(24.MHz()).freeze(&mut p.FLASH); + let mut p = pac::Peripherals::take().unwrap(); + let cp = Peripherals::take().unwrap(); + let _rcc = p.RCC.configure().sysclk(24.MHz()).freeze(&mut p.FLASH); - // Get access to individual pins in the GPIO port - let gpioa = p.GPIOA.split(); + // Get access to individual pins in the GPIO port + let gpioa = p.GPIOA.split(); - // (Re-)configure the pin connected to our LED as output - let led = gpioa.pa5.into_push_pull_output(); + // (Re-)configure the pin connected to our LED as output + let led = gpioa.pa5.into_push_pull_output(); - // Transfer GPIO into a shared structure - swap(&mut Some(led), &mut GPIO.borrow(cs).borrow_mut()); + cortex_m::interrupt::free(move |cs| { + // Transfer GPIO into a shared structure + *GPIO.borrow(cs).borrow_mut() = Some(led); + }); - let mut syst = cp.SYST; + let mut syst = cp.SYST; - // Initialise SysTick counter with a defined value - unsafe { syst.cvr.write(1) }; + // Initialise SysTick counter with a defined value + unsafe { syst.cvr.write(1) }; - // Set source for SysTick counter, here full operating frequency (== 48MHz) - syst.set_clock_source(Core); + // Set source for SysTick counter, here full operating frequency (== 48MHz) + syst.set_clock_source(Core); - // Set reload value, i.e. timer delay 24 MHz/2 Mcounts == 12Hz or 83ms - syst.set_reload(2_000_000 - 1); + // Set reload value, i.e. timer delay 24 MHz/2 Mcounts == 12Hz or 83ms + syst.set_reload(2_000_000 - 1); - // Start counting - syst.enable_counter(); + // Start counting + syst.enable_counter(); - // Enable interrupt generation - syst.enable_interrupt(); - }); - } + // Enable interrupt generation + syst.enable_interrupt(); - loop { - continue; - } + loop {} } // Define an exception handler, i.e. function to call when exception occurs. Here, if our SysTick diff --git a/examples/i2c_find_address.rs b/examples/i2c_find_address.rs index 5ee86bb..4d018ed 100644 --- a/examples/i2c_find_address.rs +++ b/examples/i2c_find_address.rs @@ -13,43 +13,40 @@ use cortex_m_rt::entry; use defmt::info; use embedded_hal_02::blocking::i2c::Write; -/* Example meant for py32f030xc MCUs with i2c devices connected on PB7 and PB8 */ - #[entry] fn main() -> ! { - if let Some(p) = pac::Peripherals::take() { - let mut flash = p.FLASH; - let rcc = p - .RCC - .configure() - .sysclk(24.MHz()) - .pclk(24.MHz()) - .freeze(&mut flash); - - let gpioa = p.GPIOA.split(); - - // Configure pins for I2C - let scl = gpioa.pa3.into_alternate_af12(); - let sda = gpioa.pa2.into_alternate_af12(); - - // Configure I2C with 100kHz rate - let mut i2c = I2c::i2c(p.I2C, (scl, sda), 100.kHz(), &rcc.clocks); - - let mut devices = 0; - // I2C addresses are 7-bit wide, covering the 0-127 range - for add in 0..=127 { - // The write method sends the specified address and checks for acknowledgement; - // if no ack is given by the slave device the result is Err(), otherwise Ok() - // Since we only care for an acknowledgement the data sent can be empty - if i2c.write(add, &[]).is_ok() { - devices += 1; - } + let p = pac::Peripherals::take().unwrap(); + let mut flash = p.FLASH; + let rcc = p + .RCC + .configure() + .sysclk(24.MHz()) + .pclk(24.MHz()) + .freeze(&mut flash); + + let gpioa = p.GPIOA.split(); + + // Configure pins for I2C + let scl = gpioa.pa3.into_alternate_af12(); + let sda = gpioa.pa2.into_alternate_af12(); + + // Configure I2C with 100kHz rate + let mut i2c = I2c::i2c(p.I2C, (scl, sda), 100.kHz(), &rcc.clocks); + + let mut devices = 0; + // I2C addresses are 7-bit wide, covering the 0-127 range + for add in 0..=127 { + // The write method sends the specified address and checks for acknowledgement; + // if no ack is given by the slave device the result is Err(), otherwise Ok() + // Since we only care for an acknowledgement the data sent can be empty + if i2c.write(add, &[]).is_ok() { + devices += 1; } - - // Here the variable "_devices" counts how many i2c addresses were a hit - info!("{} devices find.\r\n", devices); } + // Here the variable "_devices" counts how many i2c addresses were a hit + info!("{} devices find.\r\n", devices); + loop { continue; } diff --git a/examples/led_hal_button_irq.rs b/examples/led_hal_button_irq.rs index 3469e9f..b10133f 100644 --- a/examples/led_hal_button_irq.rs +++ b/examples/led_hal_button_irq.rs @@ -7,7 +7,7 @@ use py32f0xx_hal as hal; use crate::hal::{ gpio::*, - pac::{interrupt, Interrupt, Peripherals, EXTI}, + pac::{interrupt, Interrupt, Peripherals}, prelude::*, timer::SysDelay, }; @@ -24,88 +24,83 @@ static LED: Mutex>>>> = Mutex::new(Re // Make our delay provider globally available static DELAY: Mutex>> = Mutex::new(RefCell::new(None)); -// Make external interrupt registers globally available -static INT: Mutex>> = Mutex::new(RefCell::new(None)); +// Make button pin globally available +static INT: Mutex>>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { - if let (Some(p), Some(cp)) = (Peripherals::take(), c_m_Peripherals::take()) { - cortex_m::interrupt::free(move |cs| { - // Enable clock for SYSCFG - let rcc = p.RCC; - rcc.apbenr2.modify(|_, w| w.syscfgen().set_bit()); - - let mut flash = p.FLASH; - let rcc = rcc.configure().sysclk(8.MHz()).freeze(&mut flash); - - let gpioa = p.GPIOA.split(); - let gpiob = p.GPIOB.split(); - let exti = p.EXTI; - - // Configure PB2 as input (button) - let _ = gpiob.pb2.into_pull_down_input(); - - // Configure PA5 as output (LED) - let mut led = gpioa.pa5.into_push_pull_output(); - - // Turn off LED - led.set_low(); - - // Initialise delay provider - let delay = cp.SYST.delay(&rcc.clocks); - - // Enable external interrupt for PB2 - exti.exticr1.modify(|_, w| w.exti2().pb()); - - // Set interrupt request mask for line 2 - exti.imr.modify(|_, w| w.im2().set_bit()); - - // Set interrupt rising trigger for line 2 - exti.rtsr.modify(|_, w| w.rt2().set_bit()); - - // Move control over LED and DELAY and EXTI into global mutexes - *LED.borrow(cs).borrow_mut() = Some(led); - *DELAY.borrow(cs).borrow_mut() = Some(delay); - *INT.borrow(cs).borrow_mut() = Some(exti); + let mut p = Peripherals::take().unwrap(); + let cp = c_m_Peripherals::take().unwrap(); + // Enable clock for SYSCFG + let rcc = p.RCC; + rcc.apbenr2.modify(|_, w| w.syscfgen().set_bit()); + + let mut flash = p.FLASH; + let rcc = rcc.configure().sysclk(24.MHz()).freeze(&mut flash); + + let gpioa = p.GPIOA.split(); + let gpiob = p.GPIOB.split(); + + // Configure PB2 as input (button) + let mut int_pin = gpiob.pb2.into_pull_down_input(); + int_pin.make_interrupt_source(&mut p.EXTI); + int_pin.trigger_on_edge(&mut p.EXTI, Edge::Rising); + int_pin.enable_interrupt(&mut p.EXTI); + + // Configure PA5 as output (LED) + let mut led = gpioa.pa5.into_push_pull_output(); + + // Turn off LED + led.set_low(); + + // Initialise delay provider + let delay = cp.SYST.delay(&rcc.clocks); + + // Move control over LED and DELAY and EXTI into global mutexes + cortex_m::interrupt::free(move |cs| { + *LED.borrow(cs).borrow_mut() = Some(led); + *DELAY.borrow(cs).borrow_mut() = Some(delay); + *INT.borrow(cs).borrow_mut() = Some(int_pin); + }); - // Enable EXTI IRQ, set prio 1 and clear any pending IRQs - let mut nvic = cp.NVIC; - unsafe { - nvic.set_priority(Interrupt::EXTI2_3, 1); - cortex_m::peripheral::NVIC::unmask(Interrupt::EXTI2_3); - } - cortex_m::peripheral::NVIC::unpend(Interrupt::EXTI2_3); - }); + // Enable EXTI IRQ, set prio 1 and clear any pending IRQs + let mut nvic = cp.NVIC; + unsafe { + nvic.set_priority(Interrupt::EXTI2_3, 1); + cortex_m::peripheral::NVIC::unmask(Interrupt::EXTI2_3); } + cortex_m::peripheral::NVIC::unpend(Interrupt::EXTI2_3); loop { continue; } } -// Define an interupt handler, i.e. function to call when interrupt occurs. Here if our external +// Define an interrupt handler, i.e. function to call when interrupt occurs. Here if our external // interrupt trips when the button is pressed and will light the LED for a second #[interrupt] fn EXTI2_3() { // Enter critical section cortex_m::interrupt::free(|cs| { // Obtain all Mutex protected resources - if let (&mut Some(ref mut led), &mut Some(ref mut delay), &mut Some(ref mut exti)) = ( + if let (&mut Some(ref mut led), &mut Some(ref mut delay), &mut Some(ref mut int_pin)) = ( LED.borrow(cs).borrow_mut().deref_mut(), DELAY.borrow(cs).borrow_mut().deref_mut(), INT.borrow(cs).borrow_mut().deref_mut(), ) { - // Turn on LED - led.set_high(); + if int_pin.check_interrupt() { + // Turn on LED + led.set_high(); - // Wait a second - delay.delay_ms(1_000_u16); + // Wait a second + delay.delay_ms(1_000_u16); - // Turn off LED - led.set_low(); + // Turn off LED + led.set_low(); - // Clear event triggering the interrupt - exti.pr.write(|w| w.pr2().clear()); + // Clear event triggering the interrupt + int_pin.clear_interrupt_pending_bit(); + } } }); } diff --git a/examples/pwm.rs b/examples/pwm.rs index 14ff5d3..d6e78b0 100644 --- a/examples/pwm.rs +++ b/examples/pwm.rs @@ -14,24 +14,23 @@ use hal::{pac, prelude::*, pwm}; #[entry] fn main() -> ! { - if let Some(mut dp) = pac::Peripherals::take() { - // Set up the system clock. - let rcc = dp.RCC.configure().sysclk(8.MHz()).freeze(&mut dp.FLASH); - - let gpioa = dp.GPIOA.split(); - let channels = ( - gpioa.pa8.into_alternate_af2(), // on TIM1_CH1 - gpioa.pa9.into_alternate_af2(), // on TIM1_CH2 - ); - - let pwm = pwm::tim1(dp.TIM1, channels, &rcc.clocks, 20.kHz()); - let (mut ch1, mut ch2) = pwm; - let max_duty = ch1.get_max_duty(); - ch1.set_duty(max_duty / 2); - ch1.enable(); - ch2.set_duty(max_duty * 9 / 10); - ch2.enable(); - } + let mut dp = pac::Peripherals::take().unwrap(); + // Set up the system clock. + let rcc = dp.RCC.configure().sysclk(24.MHz()).freeze(&mut dp.FLASH); + + let gpioa = dp.GPIOA.split(); + let channels = ( + gpioa.pa8.into_alternate_af2(), // on TIM1_CH1 + gpioa.pa9.into_alternate_af2(), // on TIM1_CH2 + ); + + let pwm = pwm::tim1(dp.TIM1, channels, &rcc.clocks, 20.kHz()); + let (mut ch1, mut ch2) = pwm; + let max_duty = ch1.get_max_duty(); + ch1.set_duty(max_duty / 2); + ch1.enable(); + ch2.set_duty(max_duty * 9 / 10); + ch2.enable(); loop { cortex_m::asm::nop(); diff --git a/examples/pwm_complementary.rs b/examples/pwm_complementary.rs index 038d130..138831c 100644 --- a/examples/pwm_complementary.rs +++ b/examples/pwm_complementary.rs @@ -16,45 +16,38 @@ use hal::{pac, prelude::*, pwm}; #[entry] fn main() -> ! { - if let Some(mut dp) = pac::Peripherals::take() { - // Set up the system clock. - let rcc = dp.RCC.configure().sysclk(8.MHz()).freeze(&mut dp.FLASH); - - let gpioa = dp.GPIOA.split(); - let channels = ( - gpioa.pa8.into_alternate_af2(), // on TIM1_CH1 - gpioa.pa7.into_alternate_af2(), // on TIM1_CH1N - ); - - let pwm = pwm::tim1(dp.TIM1, channels, &rcc.clocks, 20.kHz()); - let (mut ch1, mut ch1n) = pwm; - let max_duty = ch1.get_max_duty(); - ch1.set_duty(max_duty / 2); - ch1.enable(); - ch1n.enable(); - - // simple duty sweep - if let Some(cp) = cortex_m::Peripherals::take() { - let mut delay = cp.SYST.delay(&rcc.clocks); - - let steps = 100; - - loop { - for i in 0..steps { - ch1.set_duty(max_duty / steps * i); - delay.delay_ms(30u16); - } - - for i in (1..steps).rev() { - ch1.set_duty(max_duty / steps * i); - delay.delay_ms(30u16); - } - } - } - } + let mut dp = pac::Peripherals::take().unwrap(); + let cp = cortex_m::Peripherals::take().unwrap(); + // Set up the system clock. + let rcc = dp.RCC.configure().sysclk(24.MHz()).freeze(&mut dp.FLASH); + + let gpioa = dp.GPIOA.split(); + let channels = ( + gpioa.pa8.into_alternate_af2(), // on TIM1_CH1 + gpioa.pa7.into_alternate_af2(), // on TIM1_CH1N + ); + + let pwm = pwm::tim1(dp.TIM1, channels, &rcc.clocks, 20.kHz()); + let (mut ch1, mut ch1n) = pwm; + let max_duty = ch1.get_max_duty(); + ch1.set_duty(max_duty / 2); + ch1.enable(); + ch1n.enable(); + + // simple duty sweep + let mut delay = cp.SYST.delay(&rcc.clocks); + + let steps = 100; - // something went wrong when acquiring peripheral access loop { - cortex_m::asm::nop(); + for i in 0..steps { + ch1.set_duty(max_duty / steps * i); + delay.delay_ms(30u16); + } + + for i in (1..steps).rev() { + ch1.set_duty(max_duty / steps * i); + delay.delay_ms(30u16); + } } } diff --git a/examples/serial_echo.rs b/examples/serial_echo.rs index abf1fa8..e369087 100644 --- a/examples/serial_echo.rs +++ b/examples/serial_echo.rs @@ -18,37 +18,31 @@ use embedded_hal_02::serial::{Read, Write as OtherWrite}; #[entry] fn main() -> ! { - if let Some(p) = pac::Peripherals::take() { - let mut flash = p.FLASH; - let rcc = p - .RCC - .configure() - .hsi(HSIFreq::Freq24mhz) - .sysclk(24.MHz()) - .freeze(&mut flash); - - rcc.configure_mco(MCOSrc::Sysclk, MCODiv::NotDivided); - - let gpioa = p.GPIOA.split(); - - let (tx, rx) = ( - gpioa.pa2.into_alternate_af1(), - gpioa.pa3.into_alternate_af1(), - ); - - let mut serial = p.USART1.serial((tx, rx), 115_200.bps(), &rcc.clocks); - serial.write_str("Input any key:\n").ok(); - - loop { - // Wait for reception of a single byte - let received: u8 = nb::block!(serial.read()).unwrap(); - - // Send back previously received byte and wait for completion - nb::block!(serial.write(received)).ok(); - } - } + let p = pac::Peripherals::take().unwrap(); + let mut flash = p.FLASH; + let rcc = p + .RCC + .configure() + .hsi(HSIFreq::Freq24mhz) + .sysclk(24.MHz()) + .freeze(&mut flash); + rcc.configure_mco(MCOSrc::Sysclk, MCODiv::NotDivided); + + let gpioa = p.GPIOA.split(); + + let (tx, rx) = ( + gpioa.pa2.into_alternate_af1(), + gpioa.pa3.into_alternate_af1(), + ); + + let mut serial = p.USART1.serial((tx, rx), 115_200.bps(), &rcc.clocks); + serial.write_str("Input any key:\r\n").ok(); loop { - continue; + // Wait for reception of a single byte + let received: u8 = nb::block!(serial.read()).unwrap(); + + // Send back previously received byte and wait for completion + nb::block!(serial.write(received)).ok(); } } diff --git a/examples/serial_spi_bridge.rs b/examples/serial_spi_bridge.rs index 0c010e1..1881f03 100644 --- a/examples/serial_spi_bridge.rs +++ b/examples/serial_spi_bridge.rs @@ -29,43 +29,39 @@ fn main() -> ! { phase: Phase::CaptureOnSecondTransition, }; - if let Some(p) = pac::Peripherals::take() { - let mut flash = p.FLASH; - let rcc = p.RCC.configure().freeze(&mut flash); + let p = pac::Peripherals::take().unwrap(); + let mut flash = p.FLASH; + let rcc = p.RCC.configure().freeze(&mut flash); - let gpioa = p.GPIOA.split(); + let gpioa = p.GPIOA.split(); - let (sck, miso, mosi, tx, rx) = ( - // SPI pins - gpioa.pa5.into_alternate_af0(), - gpioa.pa6.into_alternate_af0(), - gpioa.pa7.into_alternate_af0(), - // USART pins - gpioa.pa2.into_alternate_af1(), - gpioa.pa3.into_alternate_af1(), - ); + let (sck, miso, mosi, tx, rx) = ( + // SPI pins + gpioa.pa5.into_alternate_af0(), + gpioa.pa6.into_alternate_af0(), + gpioa.pa7.into_alternate_af0(), + // USART pins + gpioa.pa2.into_alternate_af1(), + gpioa.pa3.into_alternate_af1(), + ); - // Configure SPI with 1MHz rate - let mut spi = p.SPI1.spi( - (Some(sck), Some(miso), Some(mosi)), - MODE, - 1.MHz().into(), - &rcc.clocks, - ); + // Configure SPI with 1MHz rate + let mut spi = p.SPI1.spi( + (Some(sck), Some(miso), Some(mosi)), + MODE, + 1.MHz(), + &rcc.clocks, + ); - let mut serial = p.USART1.serial((tx, rx), 115_200.bps(), &rcc.clocks); + let mut serial = p.USART1.serial((tx, rx), 115_200.bps(), &rcc.clocks); - let mut datatx = [0]; - let datarx = [0]; - loop { - let serial_received = block!(serial.rx.read()).unwrap(); - spi.write(&[serial_received]).ok(); - spi.transfer(&mut datatx, &datarx).unwrap(); - block!(serial.tx.write_u8(datarx[0])).ok(); - } - } + let mut datatx = [0]; + let datarx = [0]; loop { - continue; + let serial_received = block!(serial.rx.read()).unwrap(); + spi.write(&[serial_received]).ok(); + spi.transfer(&mut datatx, &datarx).unwrap(); + block!(serial.tx.write_u8(datarx[0])).ok(); } } diff --git a/examples/serial_stopwatch.rs b/examples/serial_stopwatch.rs index 6fbae54..033b14c 100644 --- a/examples/serial_stopwatch.rs +++ b/examples/serial_stopwatch.rs @@ -54,67 +54,64 @@ fn TIM16() { #[entry] fn main() -> ! { - if let (Some(p), Some(cp)) = (Peripherals::take(), c_m_Peripherals::take()) { - let mut serial = cortex_m::interrupt::free(move |cs| { - let mut flash = p.FLASH; - let rcc = p.RCC.configure().sysclk(24.MHz()).freeze(&mut flash); - - // Use USART1 with PA2 and PA3 as serial port - let gpioa = p.GPIOA.split(); - let tx = gpioa.pa2.into_alternate_af1(); - let rx = gpioa.pa3.into_alternate_af1(); - - // Set up a timer expiring every millisecond - let mut timer = p.TIM16.counter_ms(&rcc.clocks); - - // Generate an interrupt when the timer expires - timer.listen(Event::Update); - timer.start(1.millis()).unwrap(); - - // Move the timer into our global storage - *GINT.borrow(cs).borrow_mut() = Some(timer); - - // Enable TIM1 IRQ, set prio 1 and clear any pending IRQs - let mut nvic = cp.NVIC; - unsafe { - nvic.set_priority(Interrupt::TIM16, 1); - cortex_m::peripheral::NVIC::unmask(Interrupt::TIM16); - } - cortex_m::peripheral::NVIC::unpend(Interrupt::TIM16); - - // Set up our serial port - p.USART1.serial((tx, rx), 115_200.bps(), &rcc.clocks) - }); + let p = Peripherals::take().unwrap(); + let cp = c_m_Peripherals::take().unwrap(); - // Print a welcome message - writeln!( - serial, - "Welcome to the stop watch, hit any key to see the current value and 0 to reset\r", - ) - .ok(); + let mut flash = p.FLASH; + let rcc = p.RCC.configure().sysclk(24.MHz()).freeze(&mut flash); - loop { - // Wait for reception of a single byte - let received = nb::block!(serial.rx.read()).unwrap(); + // Use USART1 with PA2 and PA3 as serial port + let gpioa = p.GPIOA.split(); + let tx = gpioa.pa2.into_alternate_af1(); + let rx = gpioa.pa3.into_alternate_af1(); - let time = cortex_m::interrupt::free(|cs| { - let mut time = TIME.borrow(cs).borrow_mut(); + // Set up a timer expiring every millisecond + let mut timer = p.TIM16.counter_ms(&rcc.clocks); - // If we received a 0, reset the time - if received == b'0' { - time.millis = 0; - time.seconds = 0; - } + // Generate an interrupt when the timer expires + timer.listen(Event::Update); + timer.start(1.millis()).unwrap(); - *time - }); + cortex_m::interrupt::free(|cs| { + // Move the timer into our global storage + *GINT.borrow(cs).borrow_mut() = Some(timer); + }); - // Print the current time - writeln!(serial, "{}.{:03}s\r", time.seconds, time.millis).ok(); - } + // Enable TIM1 IRQ, set prio 1 and clear any pending IRQs + let mut nvic = cp.NVIC; + unsafe { + nvic.set_priority(Interrupt::TIM16, 1); + cortex_m::peripheral::NVIC::unmask(Interrupt::TIM16); } + cortex_m::peripheral::NVIC::unpend(Interrupt::TIM16); + + // Set up our serial port + let mut serial = p.USART1.serial((tx, rx), 115_200.bps(), &rcc.clocks); + + // Print a welcome message + writeln!( + serial, + "Welcome to the stop watch, hit any key to see the current value and 0 to reset\r", + ) + .ok(); loop { - continue; + // Wait for reception of a single byte + let received = nb::block!(serial.rx.read()).unwrap(); + + let time = cortex_m::interrupt::free(|cs| { + let mut time = TIME.borrow(cs).borrow_mut(); + + // If we received a 0, reset the time + if received == b'0' { + time.millis = 0; + time.seconds = 0; + } + + *time + }); + + // Print the current time + writeln!(serial, "{}.{:03}s\r", time.seconds, time.millis).ok(); } } diff --git a/examples/spi_hal_apa102c.rs b/examples/spi_hal_apa102c.rs index 000dd98..6219b21 100644 --- a/examples/spi_hal_apa102c.rs +++ b/examples/spi_hal_apa102c.rs @@ -20,54 +20,49 @@ fn main() -> ! { phase: Phase::CaptureOnSecondTransition, }; - if let Some(p) = pac::Peripherals::take() { - let mut flash = p.FLASH; - let rcc = p.RCC.configure().freeze(&mut flash); + let p = pac::Peripherals::take().unwrap(); + let mut flash = p.FLASH; + let rcc = p.RCC.configure().freeze(&mut flash); - let gpioa = p.GPIOA.split(); + let gpioa = p.GPIOA.split(); - // Configure pins for SPI - let (sck, miso, mosi) = ( - gpioa.pa5.into_alternate_af0(), - gpioa.pa6.into_alternate_af0(), - gpioa.pa7.into_alternate_af0(), - ); + // Configure pins for SPI + let (sck, miso, mosi) = ( + gpioa.pa5.into_alternate_af0(), + gpioa.pa6.into_alternate_af0(), + gpioa.pa7.into_alternate_af0(), + ); - // Configure SPI with 100kHz rate - let mut spi = p.SPI1.spi( - (Some(sck), Some(miso), Some(mosi)), - MODE, - 100_000.Hz(), - &rcc.clocks, - ); + // Configure SPI with 100kHz rate + let mut spi = p.SPI1.spi( + (Some(sck), Some(miso), Some(mosi)), + MODE, + 100_000.Hz(), + &rcc.clocks, + ); - // Cycle through colors on 16 chained APA102C LEDs - loop { - for r in 0..255 { - let _ = spi.write(&[0, 0, 0, 0]); - for _i in 0..16 { - let _ = spi.write(&[0b1110_0001, 0, 0, r]); - } - let _ = spi.write(&[0xFF, 0xFF, 0xFF, 0xFF]); + // Cycle through colors on 16 chained APA102C LEDs + loop { + for r in 0..255 { + let _ = spi.write(&[0, 0, 0, 0]); + for _i in 0..16 { + let _ = spi.write(&[0b1110_0001, 0, 0, r]); } - for b in 0..255 { - let _ = spi.write(&[0, 0, 0, 0]); - for _i in 0..16 { - let _ = spi.write(&[0b1110_0001, b, 0, 0]); - } - let _ = spi.write(&[0xFF, 0xFF, 0xFF, 0xFF]); + let _ = spi.write(&[0xFF, 0xFF, 0xFF, 0xFF]); + } + for b in 0..255 { + let _ = spi.write(&[0, 0, 0, 0]); + for _i in 0..16 { + let _ = spi.write(&[0b1110_0001, b, 0, 0]); } - for g in 0..255 { - let _ = spi.write(&[0, 0, 0, 0]); - for _i in 0..16 { - let _ = spi.write(&[0b1110_0001, 0, g, 0]); - } - let _ = spi.write(&[0xFF, 0xFF, 0xFF, 0xFF]); + let _ = spi.write(&[0xFF, 0xFF, 0xFF, 0xFF]); + } + for g in 0..255 { + let _ = spi.write(&[0, 0, 0, 0]); + for _i in 0..16 { + let _ = spi.write(&[0b1110_0001, 0, g, 0]); } + let _ = spi.write(&[0xFF, 0xFF, 0xFF, 0xFF]); } } - - loop { - continue; - } } diff --git a/examples/spi_rc522.rs b/examples/spi_rc522.rs index 77b01e2..d6b7ada 100644 --- a/examples/spi_rc522.rs +++ b/examples/spi_rc522.rs @@ -31,67 +31,61 @@ fn main() -> ! { phase: Phase::CaptureOnSecondTransition, }; - if let (Some(p), Some(cp)) = ( - pac::Peripherals::take(), - cortex_m::peripheral::Peripherals::take(), - ) { - let mut flash = p.FLASH; - let rcc = p.RCC.configure().freeze(&mut flash); - - let mut delay = cp.SYST.delay(&rcc.clocks); - - let gpioa = p.GPIOA.split(); - - let (sck, miso, mosi, nss, mut rst) = ( - // SPI pins - gpioa.pa5.into_alternate_af0(), - gpioa.pa6.into_alternate_af0(), - gpioa.pa7.into_alternate_af0(), - // Aux pins - gpioa.pa4.into_push_pull_output(), - gpioa.pa1.into_push_pull_output(), - ); - rst.set_low(); - - // Configure SPI with 1MHz rate - let spi = p.SPI1.spi( - (Some(sck), Some(miso), Some(mosi)), - MODE, - 1.MHz().into(), - &rcc.clocks, - ); - let itf = SpiInterface::new(spi).with_nss(nss).with_delay(|| { - delay.delay_ms(1_u16); - }); - rst.set_high(); - - let mut mfrc522 = Mfrc522::new(itf).init().unwrap(); - - let ver = mfrc522.version().unwrap(); - info!("MFRC522 version: 0x{:02x}", ver); - assert!(ver == 0x91 || ver == 0x92); - - let mut timer = p.TIM1.counter_hz(&rcc.clocks); - timer.start(1.Hz()).unwrap(); - - loop { - info!("Waiting for card..."); - match mfrc522.reqa() { - Ok(atqa) => { - if let Ok(uid) = mfrc522.select(&atqa) { - info!("Selected card, UID: {:02X}", uid.as_bytes()); - } else { - error!("Failed to select card"); - } + let p = pac::Peripherals::take().unwrap(); + let cp = cortex_m::Peripherals::take().unwrap(); + + let mut flash = p.FLASH; + let rcc = p.RCC.configure().freeze(&mut flash); + + let mut delay = cp.SYST.delay(&rcc.clocks); + + let gpioa = p.GPIOA.split(); + + let (sck, miso, mosi, nss, mut rst) = ( + // SPI pins + gpioa.pa5.into_alternate_af0(), + gpioa.pa6.into_alternate_af0(), + gpioa.pa7.into_alternate_af0(), + // Aux pins + gpioa.pa4.into_push_pull_output(), + gpioa.pa1.into_push_pull_output(), + ); + rst.set_low(); + + // Configure SPI with 1MHz rate + let spi = p.SPI1.spi( + (Some(sck), Some(miso), Some(mosi)), + MODE, + 1.MHz(), + &rcc.clocks, + ); + let itf = SpiInterface::new(spi).with_nss(nss).with_delay(|| { + delay.delay_ms(1_u16); + }); + rst.set_high(); + + let mut mfrc522 = Mfrc522::new(itf).init().unwrap(); + + let ver = mfrc522.version().unwrap(); + info!("MFRC522 version: 0x{:02x}", ver); + assert!(ver == 0x91 || ver == 0x92); + + let mut timer = p.TIM1.counter_hz(&rcc.clocks); + timer.start(1.Hz()).unwrap(); + + loop { + info!("Waiting for card..."); + match mfrc522.reqa() { + Ok(atqa) => { + if let Ok(uid) = mfrc522.select(&atqa) { + info!("Selected card, UID: {:02X}", uid.as_bytes()); + } else { + error!("Failed to select card"); } - Err(_e) => error!("Error when requesting ATQA!"), } - - nb::block!(timer.wait()).unwrap(); + Err(_e) => error!("Error when requesting ATQA!"), } - } - loop { - continue; + nb::block!(timer.wait()).unwrap(); } } diff --git a/examples/watchdog.rs b/examples/watchdog.rs index 6b13c99..7fe7679 100644 --- a/examples/watchdog.rs +++ b/examples/watchdog.rs @@ -14,46 +14,44 @@ use embedded_hal_02::watchdog::{Watchdog, WatchdogEnable}; #[entry] fn main() -> ! { - if let (Some(p), Some(cp)) = (pac::Peripherals::take(), Peripherals::take()) { - let mut flash = p.FLASH; - let mut rcc = p.RCC.configure().sysclk(8.MHz()).freeze(&mut flash); + let p = pac::Peripherals::take().unwrap(); + let cp = Peripherals::take().unwrap(); - let gpioa = p.GPIOA.split(); - let dbg = p.DBG; + let mut flash = p.FLASH; + let mut rcc = p.RCC.configure().sysclk(24.MHz()).freeze(&mut flash); - // Disable the watchdog when the cpu is stopped under debug - dbg.apb_fz1.modify(|_, w| w.dbg_iwdg_stop().set_bit()); + let gpioa = p.GPIOA.split(); + let dbg = p.DBG; - let mut watchdog = watchdog::Watchdog::new(&mut rcc, p.IWDG); + // Disable the watchdog when the cpu is stopped under debug + dbg.apb_fz1.modify(|_, w| w.dbg_iwdg_stop().set_bit()); - // Get delay provider - let mut delay = cp.SYST.delay(&rcc.clocks); + let mut watchdog = watchdog::Watchdog::new(&mut rcc, p.IWDG); - // Configure serial TX pin - let tx = gpioa.pa2.into_alternate_af1(); + // Get delay provider + let mut delay = cp.SYST.delay(&rcc.clocks); - // Obtain a serial peripheral with unidirectional communication - let mut serial = p.USART1.tx(tx, 115_200.bps(), &rcc.clocks); + // Configure serial TX pin + let tx = gpioa.pa2.into_alternate_af1(); - serial.write_str("RESET \r\n").ok(); + // Obtain a serial peripheral with unidirectional communication + let mut serial = p.USART1.tx(tx, 115_200.bps(), &rcc.clocks); - watchdog.start(1.Hz()); - delay.delay_ms(500_u16); - watchdog.feed(); - serial.write_str("Feed the dog 1st\r\n").ok(); - delay.delay_ms(500_u16); - watchdog.feed(); - serial.write_str("Feed the dog 2nd\r\n").ok(); - delay.delay_ms(500_u16); - watchdog.feed(); - serial.write_str("Feed the dog 3rd\r\n").ok(); + serial.write_str("RESET \r\n").ok(); - // Now a reset happens while delaying - delay.delay_ms(1500_u16); - serial.write_str("This won't\r\n").ok(); - } + watchdog.start(1.Hz()); + delay.delay_ms(500_u16); + watchdog.feed(); + serial.write_str("Feed the dog 1st\r\n").ok(); + delay.delay_ms(500_u16); + watchdog.feed(); + serial.write_str("Feed the dog 2nd\r\n").ok(); + delay.delay_ms(500_u16); + watchdog.feed(); + serial.write_str("Feed the dog 3rd\r\n").ok(); - loop { - continue; - } + // Now a reset happens while delaying + delay.delay_ms(1500_u16); + serial.write_str("This won't\r\n").ok(); + loop {} } diff --git a/src/rcc.rs b/src/rcc.rs index a120895..844183c 100644 --- a/src/rcc.rs +++ b/src/rcc.rs @@ -604,7 +604,7 @@ impl CFGR { clocks: Clocks { hclk: Hz(hclk), pclk: Hz(pclk), - sysclk: Hz(sysclk), + sysclk: Hz(r_sysclk), ppre, }, regs: self.rcc, diff --git a/src/timer.rs b/src/timer.rs index a8cbbce..3c59254 100644 --- a/src/timer.rs +++ b/src/timer.rs @@ -31,7 +31,7 @@ use crate::pac::{self, DBG}; use crate::rcc::{BusTimerClock, Clocks, Enable, Reset}; -use crate::time::{Hertz, Hz}; +use crate::time::Hertz; use core::convert::TryFrom; use cortex_m::peripheral::syst::SystClkSource; use cortex_m::peripheral::SYST; @@ -166,23 +166,23 @@ impl Timer { } } - /// Initialize SysTick timer and set it frequency to `HCLK / 8` + /// Initialize SysTick timer and set it frequency to `HCLK` pub fn syst_external(mut tim: SYST, clocks: &Clocks) -> Self { tim.set_clock_source(SystClkSource::External); Self { tim, - clk: Hz(clocks.hclk().raw() / 8), + clk: clocks.hclk(), } } pub fn configure(&mut self, clocks: &Clocks) { self.tim.set_clock_source(SystClkSource::Core); - self.clk = clocks.hclk(); + self.clk = clocks.sysclk(); } pub fn configure_external(&mut self, clocks: &Clocks) { self.tim.set_clock_source(SystClkSource::External); - self.clk = Hz(clocks.hclk().raw() / 8); + self.clk = clocks.hclk(); } pub fn release(self) -> SYST { From 48444d986602ff7d60fa2d9cc442edc2f45b70d0 Mon Sep 17 00:00:00 2001 From: Greg Green Date: Tue, 21 Jan 2025 21:59:14 -0800 Subject: [PATCH 11/11] Finalized CHANGELOG.md --- CHANGELOG.md | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index bf306d7..9f956d4 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -2,7 +2,7 @@ All notable changes to this project will be documented in this file. -## Unreleased +## v0.2.0 This version depends on py32-rs v0.2.0 or later @@ -28,7 +28,7 @@ This version depends on py32-rs v0.2.0 or later * `as_pull_down_input` - module `rcc` * new traits and implementations `Enable`, `Reset`, `BusClock`, `BusTimerClock`, `RccBus` - * added function `debug_stop_mode` for control of clock function in sleep and stop conditions + * added function `debug_stop_mode` for control of clock function in sleep and stop conditions - added module `rtc` and examples thereof - module `serial` * Implemented embedded-hal v1.0 nb::Read/Write traits @@ -44,11 +44,13 @@ This version depends on py32-rs v0.2.0 or later * Works with both 8 and 16 bit words, though 16bit not tested * Added `SpiSlave` for slave functionality, though it is not tested * Added frame size conversion methods, [ex: `frame_size_8_bit`] +- module `timer` + * Old module `timers` was removed. Now follows both hal 1.0 and 0.2.7 traits ### Changed - Fixed repo url's -- Changed all examples to use new api's where necessary +- Changed all examples to use new api's where necessary, and to remove code structure that was causing much of the example to be optimized away - module `adc` changed to use new rcc enable, reset, and bus frequencies - module `gpio` * pin `into_` fns have removed the atomic context parameter which is not needed depending on what OS is used @@ -64,14 +66,13 @@ This version depends on py32-rs v0.2.0 or later - module `spi` * embedded-hal v0.2.7 trait implementations moved to spi/hal_02 module * changed to use rcc enable, reset, and bus frequencies -- module `time` changed to use fugit crate, this alters how you specify frequency, ie, hz -> Hz, etc. -- module `timers` - * changed to use rcc enable, reset, and bus frequencies +- module `time` changed to use fugit crate, this alters how you specify frequency, ie, hz -> Hz, etc ### Removed - `delay` and `timers` modules removed, the functionality is in the `timer` module now - `spi::Event::Crc` removed, as that doesn't exist on this micro +- `timers` module removed, replaced by `timer` ### Fixed