Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ and this project adheres to [Semantic Versioning](http://semver.org/).
### Changed

- `timer.rs` refactoring
- Add `rcc::Instance` trait

## [v0.11.0] - 2025-09-09

Expand Down
7 changes: 2 additions & 5 deletions src/adc.rs
Original file line number Diff line number Diff line change
@@ -1,15 +1,14 @@
//! # API for the Analog to Digital converter

use core::marker::PhantomData;
use core::ops::Deref;
use embedded_hal_02::adc::{Channel, OneShot};
use fugit::HertzU32 as Hertz;

#[cfg(all(feature = "stm32f103", any(feature = "high", feature = "xl")))]
use crate::dma::dma2;
use crate::dma::{dma1, CircBuffer, Receive, RxDma, Transfer, TransferPayload, W};
use crate::gpio::{self, Analog};
use crate::rcc::{Enable, Rcc, Reset};
use crate::rcc::Rcc;
use crate::time::kHz;
use core::sync::atomic::{self, Ordering};
use cortex_m::asm::delay;
Expand Down Expand Up @@ -179,9 +178,7 @@ adc_pins!(pac::ADC3,
#[derive(Copy, Clone, Debug, PartialEq, Eq, Default)]
pub struct StoredConfig(SampleTime, Align);

pub trait Instance:
crate::Sealed + crate::Ptr<RB: AdcRB> + Deref<Target = Self::RB> + Reset + Enable
{
pub trait Instance: crate::rcc::Instance + crate::Ptr<RB: AdcRB> {
type ExtSel;
#[doc(hidden)]
fn set_extsel(&self, trigger: Self::ExtSel);
Expand Down
2 changes: 1 addition & 1 deletion src/can.rs
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ impl<CAN: Instance> CanExt for CAN {
}
}

pub trait Instance: crate::rcc::Enable + afio::CanCommon {}
pub trait Instance: crate::rcc::Instance + afio::CanCommon {}
#[cfg(not(feature = "connectivity"))]
use pac::CAN as CAN1;
#[cfg(feature = "connectivity")]
Expand Down
12 changes: 3 additions & 9 deletions src/i2c.rs
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,8 @@

use crate::afio::{self, RInto, Rmp};
use crate::pac::{self, i2c1};
use crate::rcc::{BusClock, Clocks, Enable, Rcc, Reset};
use crate::rcc::{BusClock, Clocks, Rcc};
use crate::time::{kHz, Hertz};
use core::ops::Deref;

pub mod blocking;
pub use blocking::BlockingI2c;
Expand Down Expand Up @@ -115,12 +114,7 @@ pub struct I2c<I2C: Instance> {
}

pub trait Instance:
crate::Sealed
+ Deref<Target = crate::pac::i2c1::RegisterBlock>
+ Enable
+ Reset
+ BusClock
+ afio::I2cCommon
crate::rcc::Instance + crate::Ptr<RB = crate::pac::i2c1::RegisterBlock> + afio::I2cCommon
{
}

Expand Down Expand Up @@ -151,7 +145,7 @@ impl<I2C: Instance, const R: u8> Rmp<I2C, R> {
I2C::enable(rcc);
I2C::reset(rcc);

let pclk1 = I2C::clock(&rcc.clocks);
let pclk1 = I2C::Bus::clock(&rcc.clocks);

assert!(mode.get_frequency() <= kHz(400));

Expand Down
26 changes: 6 additions & 20 deletions src/rcc.rs
Original file line number Diff line number Diff line change
Expand Up @@ -429,6 +429,12 @@ impl Clocks {
}
}

/// Common trait for most of peripherals
pub trait Instance:
crate::Ptr + crate::Steal + Enable + Reset + RccBus<Bus: BusClock> + Deref<Target = Self::RB>
{
}

/// Frequency on bus that peripheral is connected in
pub trait BusClock {
/// Calculates frequency depending on `Clock` state
Expand All @@ -441,26 +447,6 @@ pub trait BusTimerClock {
fn timer_clock(clocks: &Clocks) -> Hertz;
}

impl<T> BusClock for T
where
T: RccBus,
T::Bus: BusClock,
{
fn clock(clocks: &Clocks) -> Hertz {
T::Bus::clock(clocks)
}
}

impl<T> 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
Expand Down
1 change: 1 addition & 0 deletions src/rcc/enable.rs
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ macro_rules! bus_reset {
macro_rules! bus {
($($PER:ident => ($busX:ty, $bit:literal),)+) => {
$(
impl crate::rcc::Instance for crate::pac::$PER {}
impl RccBus for crate::pac::$PER {
type Bus = $busX;
}
Expand Down
18 changes: 4 additions & 14 deletions src/serial.rs
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,6 @@
//! ```

use core::marker::PhantomData;
use core::ops::Deref;
use core::sync::atomic::{self, Ordering};
use embedded_dma::{ReadBuffer, WriteBuffer};

Expand All @@ -99,8 +98,8 @@ use crate::afio::{self, RInto, Rmp};
use crate::dma::dma2;
use crate::dma::{self, dma1, CircBuffer, RxDma, Transfer, TxDma};
use crate::gpio::{Floating, PushPull, UpMode};
use crate::pac::{self};
use crate::rcc::{BusClock, Clocks, Enable, Rcc, Reset};
use crate::pac;
use crate::rcc::{BusClock, Clocks, Rcc};
use crate::time::{Bps, U32Ext};

mod hal_02;
Expand Down Expand Up @@ -197,16 +196,7 @@ impl RBExt for pac::uart4::RegisterBlock {
}
}

pub trait Instance:
crate::Sealed
+ crate::Ptr<RB: RBExt>
+ Deref<Target = Self::RB>
+ Enable
+ Reset
+ BusClock
+ afio::SerialAsync
{
}
pub trait Instance: crate::rcc::Instance + crate::Ptr<RB: RBExt> + afio::SerialAsync {}

macro_rules! inst {
($($USARTX:ty;)+) => {
Expand Down Expand Up @@ -562,7 +552,7 @@ fn apply_config<USART: Instance>(config: Config, clocks: &Clocks) {
let usart = unsafe { &*USART::ptr() };

// Configure baud rate
let brr = USART::clock(clocks).raw() / config.baudrate.0;
let brr = USART::Bus::clock(clocks).raw() / config.baudrate.0;
assert!(brr >= 16, "impossible baud rate");
usart.brr().write(|w| unsafe { w.bits(brr as u16) });

Expand Down
11 changes: 3 additions & 8 deletions src/spi.rs
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ use crate::dma::dma1;
use crate::dma::dma2;
use crate::dma::{self, Receive, RxDma, RxTxDma, Transfer, TransferPayload, Transmit, TxDma};
use crate::gpio::{Floating, PushPull, UpMode};
use crate::rcc::{BusClock, Enable, Rcc, Reset};
use crate::rcc::{BusClock, Rcc};
use crate::time::Hertz;

use core::sync::atomic::{self, Ordering};
Expand Down Expand Up @@ -314,12 +314,7 @@ pub enum SpiBitFormat {
}

pub trait Instance:
crate::Sealed
+ Deref<Target = crate::pac::spi1::RegisterBlock>
+ Enable
+ Reset
+ BusClock
+ afio::SpiCommon
crate::rcc::Instance + crate::Ptr<RB = crate::pac::spi1::RegisterBlock> + afio::SpiCommon
{
}

Expand Down Expand Up @@ -348,7 +343,7 @@ impl<SPI: Instance, const R: u8> Rmp<SPI, R> {
// disable SS output
spi.cr2().write(|w| w.ssoe().clear_bit());

let br = match SPI::clock(&rcc.clocks) / freq {
let br = match SPI::Bus::clock(&rcc.clocks) / freq {
0 => unreachable!(),
1..=2 => 0b000,
3..=5 => 0b001,
Expand Down
10 changes: 5 additions & 5 deletions src/timer.rs
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@
use crate::bb;
use crate::pac::{self, DBGMCU as DBG};

use crate::rcc::{self, Clocks, Rcc};
use crate::rcc::{self, BusTimerClock, Clocks, Rcc};
use core::convert::TryFrom;
use cortex_m::peripheral::syst::SystClkSource;
use cortex_m::peripheral::SYST;
Expand Down Expand Up @@ -421,7 +421,7 @@ mod sealed {
pub(crate) use sealed::{Advanced, General, MasterTimer, WithCapture, WithChannel, WithPwm};

pub trait Instance:
crate::Sealed + rcc::Enable + rcc::Reset + rcc::BusTimerClock + rcc::StopInDebug + General
rcc::Instance + rcc::RccBus<Bus: BusTimerClock> + rcc::StopInDebug + General
{
}

Expand Down Expand Up @@ -777,13 +777,13 @@ impl<TIM: Instance> Timer<TIM> {
TIM::reset(rcc);

Self {
clk: TIM::timer_clock(&rcc.clocks),
clk: TIM::Bus::timer_clock(&rcc.clocks),
tim,
}
}

pub fn configure(&mut self, clocks: &Clocks) {
self.clk = TIM::timer_clock(clocks);
self.clk = TIM::Bus::timer_clock(clocks);
}

pub fn counter_hz(self) -> CounterHz<TIM> {
Expand Down Expand Up @@ -860,7 +860,7 @@ impl<TIM: Instance, const FREQ: u32> FTimer<TIM, FREQ> {

/// Calculate prescaler depending on `Clocks` state
pub fn configure(&mut self, clocks: &Clocks) {
let clk = TIM::timer_clock(clocks);
let clk = TIM::Bus::timer_clock(clocks);
assert!(clk.raw() % FREQ == 0);
let psc = clk.raw() / FREQ;
self.tim.set_prescaler(u16::try_from(psc - 1).unwrap());
Expand Down
Loading