diff --git a/examples/comp_w_dac.rs b/examples/comp_w_dac.rs index e1313108..19213b45 100644 --- a/examples/comp_w_dac.rs +++ b/examples/comp_w_dac.rs @@ -30,7 +30,7 @@ fn main() -> ! { // Set up DAC to output to pa4 and to internal signal Dac1IntSig1 // which just so happens is compatible with comp1 let dac1ch1 = dp.DAC1.constrain((gpioa.pa4, Dac1IntSig1), &mut rcc); - let mut dac = dac1ch1.calibrate_buffer(&mut delay).enable(); + let mut dac = dac1ch1.calibrate_buffer(&mut delay).enable().freeze(); let (comp1, _comp2, ..) = dp.COMP.split(&mut rcc); let pa1 = gpioa.pa1.into_analog(); diff --git a/examples/opamp.rs b/examples/opamp.rs index e4576a7a..eb10a773 100644 --- a/examples/opamp.rs +++ b/examples/opamp.rs @@ -31,35 +31,25 @@ fn main() -> ! { let gpioa = dp.GPIOA.split(&mut rcc); let gpiob = dp.GPIOB.split(&mut rcc); - // setup opamps - let (opamp1, opamp2, opamp3, ..) = dp.OPAMP.split(&mut rcc); - - // Set up opamp1 and opamp2 in follower mode - let opamp1 = opamp1.follower(gpioa.pa1, gpioa.pa2); - let opamp2 = opamp2.follower(gpioa.pa7, InternalOutput); - - // Set up opamp1 and opamp2 in open loop mode - let opamp3 = opamp3.open_loop(gpiob.pb0, gpiob.pb2, gpiob.pb1); + let pa1 = gpioa.pa1.into_analog(); + let pa2 = gpioa.pa2.into_analog(); + let pa7 = gpioa.pa7.into_analog(); - // disable opamps - let (opamp1, pa1, pa2) = opamp1.disable(); - let (opamp2, pa7) = opamp2.disable(); + let pb0 = gpiob.pb0.into_analog(); + let pb1 = gpiob.pb1.into_analog(); + let pb2 = gpiob.pb2.into_analog(); - let (_opamp3, _pb0, _pb2, _pb1) = opamp3.disable(); + // setup opamps + let (opamp1, opamp2, opamp3, ..) = dp.OPAMP.split(&mut rcc); // Configure opamp1 with pa1 as non-inverting input and set gain to x2 - let _opamp1 = opamp1.pga( - pa1, - pa2, // Route output to pin pa2 - Gain::Gain2, - ); - - // Configure op with pa7 as non-inverting input and set gain to x4 - let opamp2 = opamp2.pga( - pa7, - InternalOutput, // Do not route output to any external pin, use internal AD instead - Gain::Gain4, - ); + let _opamp1 = opamp1.pga(&pa1, pa2, Gain::Gain2); + + // Set up opamp2 in follower mode with output routed to internal ADC + let opamp2 = opamp2.follower(&pa7, InternalOutput); + + // Set up opamp3 in open loop mode + let _opamp3 = opamp3.open_loop(&pb0, pb2, pb1); // Lock opamp2. After the opamp is locked its registers cannot be written // until the device is reset (even if using unsafe register accesses). @@ -78,15 +68,13 @@ fn main() -> ! { ); let millivolts = adc.sample_to_millivolts(sample); - info!("opamp2 thus 4x pa7: {}mV", millivolts); + info!("opamp2 thus pa7: {}mV", millivolts); delay.delay_ms(100); } #[allow(unreachable_code)] { - let (_opamp1, _pin) = _opamp1.disable(); - loop { delay.delay_ms(100); } diff --git a/src/comparator.rs b/src/comparator.rs index da174734..0a52f450 100644 --- a/src/comparator.rs +++ b/src/comparator.rs @@ -5,16 +5,18 @@ //! This code has been taken from the stm32g0xx-hal project and modified slightly to support //! STM32G4xx MCUs. +use core::borrow::Borrow; use core::marker::PhantomData; use crate::dac; use crate::exti::{Event as ExtiEvent, ExtiExt}; +use crate::gpio::{FrozenPin, IsFrozen}; use crate::gpio::{ gpioa::{PA0, PA1, PA11, PA12, PA2, PA3, PA4, PA5, PA6, PA7}, gpiob::{PB0, PB1, PB14, PB15, PB2, PB6, PB7, PB8, PB9}, gpioc::PC2, gpiof::PF4, - Analog, Alternate, AlternateOD, SignalEdge, AF2, AF3, AF8, + Alternate, AlternateOD, Analog, SignalEdge, AF2, AF3, AF8, }; #[cfg(any( @@ -139,12 +141,17 @@ pub enum Hysteresis { } /// Comparator positive input -pub trait PositiveInput { - fn setup(&self, comp: &C); +pub trait PositiveInput: crate::Sealed { + /// Setup comaprator to use this as its positive input + /// + /// # Safety + /// + /// Internal use only + unsafe fn setup(&self, comp: &mut C); } /// Comparator negative input -pub trait NegativeInput { +pub trait NegativeInput: crate::Sealed { /// Does this input use the internal reference Vrefint /// /// This only true for RefintInput @@ -155,19 +162,36 @@ pub trait NegativeInput { /// This is only relevant for `RefintInput` other than `RefintInput::VRefint` fn use_resistor_divider(&self) -> bool; - fn setup(&self, comp: &C); + /// Setup comaprator to use this as its negative input + /// + /// # Safety + /// + /// Internal use only + unsafe fn setup(&self, comp: &mut C); } macro_rules! positive_input_pin { ($COMP:ident, $pin_0:ident, $pin_1:ident) => { - impl PositiveInput<$COMP> for &$pin_0 { - fn setup(&self, comp: &$COMP) { + impl PositiveInput<$COMP> for &$pin_0 { + unsafe fn setup(&self, comp: &mut $COMP) { + comp.csr().modify(|_, w| w.inpsel().bit(false)) + } + } + + impl PositiveInput<$COMP> for $pin_0 { + unsafe fn setup(&self, comp: &mut $COMP) { comp.csr().modify(|_, w| w.inpsel().bit(false)) } } - impl PositiveInput<$COMP> for &$pin_1 { - fn setup(&self, comp: &$COMP) { + impl PositiveInput<$COMP> for &$pin_1 { + unsafe fn setup(&self, comp: &mut $COMP) { + comp.csr().modify(|_, w| w.inpsel().bit(true)) + } + } + + impl PositiveInput<$COMP> for $pin_1 { + unsafe fn setup(&self, comp: &mut $COMP) { comp.csr().modify(|_, w| w.inpsel().bit(true)) } } @@ -212,7 +236,7 @@ macro_rules! negative_input_pin_helper { false } - fn setup(&self, comp: &$COMP) { + unsafe fn setup(&self, comp: &mut $COMP) { comp.csr().modify(|_, w| unsafe { w.inmsel().bits($bits) }) } } @@ -257,6 +281,9 @@ pub enum RefintInput { VRefint = 0b011, } +impl FrozenPin for RefintInput {} +impl crate::Sealed for RefintInput {} + macro_rules! refint_input { ($($COMP:ident, )+) => {$( impl NegativeInput<$COMP> for RefintInput { @@ -266,7 +293,7 @@ macro_rules! refint_input { *self != RefintInput::VRefint } - fn setup(&self, comp: &$COMP) { + unsafe fn setup(&self, comp: &mut $COMP) { comp.csr() .modify(|_, w| unsafe { w.inmsel().bits(*self as u8) }) } @@ -285,15 +312,27 @@ refint_input!(COMP1, COMP2, COMP3, COMP4,); refint_input!(COMP5, COMP6, COMP7,); macro_rules! dac_input_helper { - ($COMP:ident: $channel:ident, $MODE:ident, $bits:expr) => { - impl NegativeInput<$COMP> for &dac::$channel<{ dac::$MODE }, ED> { + ($COMP:ident: $channel:ident, $MODE:ident, $ED:ty, $bits:expr) => { + impl NegativeInput<$COMP> for &dac::$channel<{ dac::$MODE }, $ED, IsFrozen> { const USE_VREFINT: bool = false; fn use_resistor_divider(&self) -> bool { false } - fn setup(&self, comp: &$COMP) { + unsafe fn setup(&self, comp: &mut $COMP) { + comp.csr().modify(|_, w| unsafe { w.inmsel().bits($bits) }) + } + } + + impl NegativeInput<$COMP> for dac::$channel<{ dac::$MODE }, $ED> { + const USE_VREFINT: bool = false; + + fn use_resistor_divider(&self) -> bool { + false + } + + unsafe fn setup(&self, comp: &mut $COMP) { comp.csr().modify(|_, w| unsafe { w.inmsel().bits($bits) }) } } @@ -302,8 +341,10 @@ macro_rules! dac_input_helper { macro_rules! dac_input { ($COMP:ident: $channel:ident, $bits:expr) => { - dac_input_helper!($COMP: $channel, M_MIX_SIG, $bits); - dac_input_helper!($COMP: $channel, M_INT_SIG, $bits); + dac_input_helper!($COMP: $channel, M_MIX_SIG, dac::Enabled, $bits); + dac_input_helper!($COMP: $channel, M_MIX_SIG, dac::WaveGenerator, $bits); + dac_input_helper!($COMP: $channel, M_INT_SIG, dac::Enabled, $bits); + dac_input_helper!($COMP: $channel, M_INT_SIG, dac::WaveGenerator, $bits); }; } @@ -371,27 +412,36 @@ pub struct Comparator { pub trait ComparatorExt { /// Initializes a comparator - fn comparator, N: NegativeInput>( + fn comparator( self, - positive_input: P, - negative_input: N, + positive_input: PP, + negative_input: NP, config: Config, clocks: &Clocks, - ) -> Comparator; + ) -> Comparator + where + PP: FrozenPin

+ PositiveInput, + NP: FrozenPin + NegativeInput; } macro_rules! impl_comparator { ($COMP:ty, $comp:ident, $Event:expr) => { impl ComparatorExt<$COMP> for $COMP { - fn comparator, N: NegativeInput<$COMP>>( - self, - positive_input: P, - negative_input: N, + fn comparator( + mut self, + positive_input: PP, + negative_input: NP, config: Config, clocks: &Clocks, - ) -> Comparator<$COMP, Disabled> { - positive_input.setup(&self); - negative_input.setup(&self); + ) -> Comparator<$COMP, Disabled> + where + PP: FrozenPin

+ PositiveInput<$COMP>, + NP: FrozenPin + NegativeInput<$COMP> + { + unsafe { + positive_input.borrow().setup(&mut self); + negative_input.borrow().setup(&mut self); + } // Delay for scaler voltage bridge initialization for certain negative inputs let voltage_scaler_delay = clocks.sys_clk.raw() / (1_000_000 / 200); // 200us cortex_m::asm::delay(voltage_scaler_delay); @@ -399,9 +449,9 @@ macro_rules! impl_comparator { w.hyst() .bits(config.hysteresis as u8) .scalen() - .bit(N::USE_VREFINT) + .bit(NP::USE_VREFINT) .brgen() - .bit(negative_input.use_resistor_divider()) + .bit(negative_input.borrow().use_resistor_divider()) .pol() .bit(config.inverted) }); @@ -415,13 +465,17 @@ macro_rules! impl_comparator { impl Comparator<$COMP, Disabled> { /// Initializes a comparator - pub fn $comp, N: NegativeInput<$COMP>>( + pub fn $comp( comp: $COMP, - positive_input: P, - negative_input: N, + positive_input: PP, + negative_input: NP, config: Config, clocks: &Clocks, - ) -> Self { + ) -> Self + where + PP: FrozenPin

+ PositiveInput<$COMP>, + NP: FrozenPin + NegativeInput<$COMP> + { comp.comparator(positive_input, negative_input, config, clocks) } diff --git a/src/dac.rs b/src/dac.rs index 109374c0..82b9ebc9 100644 --- a/src/dac.rs +++ b/src/dac.rs @@ -9,7 +9,7 @@ use core::marker::PhantomData; use core::mem::MaybeUninit; use crate::gpio::gpioa::{PA4, PA5, PA6}; -use crate::gpio::DefaultMode; +use crate::gpio::{DefaultMode, FrozenPin, IsFrozen, IsNotFrozen}; use crate::rcc::{self, *}; use crate::stm32::{DAC1, DAC2, DAC3, DAC4, RCC}; use hal::blocking::delay::DelayUs; @@ -64,9 +64,20 @@ impl ED for Disabled {} macro_rules! impl_dac { ($DACxCHy:ident) => { - pub struct $DACxCHy { + pub struct $DACxCHy { _enabled: PhantomData, + _frozen_state: PhantomData, } + + impl FrozenPin<$DACxCHy> for $DACxCHy{} + impl FrozenPin<$DACxCHy> for $DACxCHy{} + impl FrozenPin<$DACxCHy> for &$DACxCHy{} + impl FrozenPin<$DACxCHy> for &$DACxCHy{} + + impl crate::Sealed for $DACxCHy{} + impl crate::Sealed for $DACxCHy{} + impl crate::Sealed for &$DACxCHy{} + impl crate::Sealed for &$DACxCHy{} }; } @@ -198,6 +209,7 @@ macro_rules! dac_helper { $CX { _enabled: PhantomData, + _frozen_state: PhantomData, } } @@ -214,11 +226,12 @@ macro_rules! dac_helper { $CX { _enabled: PhantomData, + _frozen_state: PhantomData, } } } - impl $CX { + impl $CX { /// Calibrate the DAC output buffer by performing a "User /// trimming" operation. It is useful when the VDDA/VREF+ /// voltage or temperature differ from the factory trimming @@ -251,6 +264,7 @@ macro_rules! dac_helper { $CX { _enabled: PhantomData, + _frozen_state: PhantomData, } } @@ -263,13 +277,18 @@ macro_rules! dac_helper { $CX { _enabled: PhantomData, + _frozen_state: PhantomData, } } + + pub fn freeze(self) -> $CX { + $CX { _enabled: PhantomData, _frozen_state: PhantomData } + } } /// DacOut implementation available in any Enabled/Disabled /// state - impl DacOut for $CX { + impl DacOut for $CX { fn set_value(&mut self, val: u16) { let dac = unsafe { &(*<$DAC>::ptr()) }; dac.$dhrx.write(|w| unsafe { w.bits(val as u32) }); @@ -282,7 +301,7 @@ macro_rules! dac_helper { } /// Wave generator state implementation - impl $CX { + impl $CX { pub fn trigger(&mut self) { let dac = unsafe { &(*<$DAC>::ptr()) }; dac.dac_swtrgr.write(|w| { w.$swtrig().set_bit() }); diff --git a/src/gpio.rs b/src/gpio.rs index b8f6de18..b69d2177 100644 --- a/src/gpio.rs +++ b/src/gpio.rs @@ -18,7 +18,7 @@ pub trait GpioExt { } /// Type state for a gpio pin frozen to its current mode -/// +/// /// The into_alternate/analog/{x}_input/output can not be called on a pin with this state. /// The pin is thus guaranteed to stay as this type as long as the program is running. pub struct IsFrozen; @@ -26,6 +26,20 @@ pub struct IsFrozen; /// See [IsFrozen] pub struct IsNotFrozen; +/// A pin type that is guaranteed to stay in the current mode after being passed to a peripheral +/// +/// This is implemented for all owned pins since no one else can change their mode once ownership is passed on to the peripheral. +/// +/// It is also implemented for reference to a frozen pin `&$PXi`, since they can not change mode due to being frozen. +pub trait FrozenPin: crate::Sealed {} +impl FrozenPin<(B1, B2)> for (A1, A2) where A1: FrozenPin, A2: FrozenPin {} +impl FrozenPin<(B1, B2, B3)> for (A1, A2, A3) where A1: FrozenPin, A2: FrozenPin, A3: FrozenPin {} +impl FrozenPin<(B1, B2, B3, B4)> for (A1, A2, A3, A4) where A1: FrozenPin, A2: FrozenPin, A3: FrozenPin, A4: FrozenPin {} + +impl crate::Sealed for (A1, A2) where A1: crate::Sealed, A2: crate::Sealed {} +impl crate::Sealed for (A1, A2, A3) where A1: crate::Sealed, A2: crate::Sealed, A3: crate::Sealed {} +impl crate::Sealed for (A1, A2, A3, A4) where A1: crate::Sealed, A2: crate::Sealed, A3: crate::Sealed, A4: crate::Sealed {} + /// Input mode (type state) pub struct Input { _mode: PhantomData, @@ -352,6 +366,11 @@ macro_rules! gpio { _frozen_state: PhantomData, } + impl FrozenPin<$PXi> for $PXi {} + impl FrozenPin<$PXi> for &$PXi {} + impl crate::Sealed for $PXi {} + impl crate::Sealed for &$PXi {} + #[allow(clippy::from_over_into)] impl Into<$PXi>> for $PXi { fn into(self) -> $PXi> { @@ -552,7 +571,7 @@ macro_rules! gpio { } $PXi { _mode: PhantomData, _frozen_state: PhantomData } } - + pub fn freeze(self) -> $PXi { $PXi { _mode: PhantomData, _frozen_state: PhantomData } } diff --git a/src/opamp.rs b/src/opamp.rs index 0b549229..e372610a 100644 --- a/src/opamp.rs +++ b/src/opamp.rs @@ -59,7 +59,12 @@ // TODO: Add support for calibration -use core::{borrow::Borrow, marker::PhantomData}; +use crate::gpio::gpioa::{PA1, PA2, PA3, PA5, PA6, PA7, PA8}; +use crate::gpio::gpiob::{PB0, PB1, PB10, PB11, PB12, PB13, PB14, PB15, PB2}; +use crate::gpio::gpioc::{PC3, PC5}; +use crate::gpio::gpiod::{PD11, PD12, PD14, PD8, PD9}; +use crate::gpio::{Analog, FrozenPin, IsFrozen}; +use core::marker::PhantomData; /// PGA Gain pub enum Gain { @@ -84,21 +89,21 @@ pub struct Disabled { /// State type for opamp running in voltage follower mode. pub struct Follower { opamp: PhantomData, - input: Input, - output: Output, + input: PhantomData, + output: PhantomData, } /// State type for opamp running in open-loop mode. pub struct OpenLoop { opamp: PhantomData, - non_inverting: NonInverting, - inverting: Inverting, - output: Output, + non_inverting: PhantomData, + inverting: PhantomData, + output: PhantomData, } /// State type for opamp running in programmable-gain mode. pub struct Pga { opamp: PhantomData, non_inverting: PhantomData, - output: Output, + output: PhantomData, } /// State type for an opamp that has been locked. pub struct Locked { @@ -141,22 +146,25 @@ where Opamp: ConfigurePgaReg + LookupPgaGain, { /// Configures the opamp for programmable gain operation. - fn pga>( + fn pga( self, - non_inverting: B, - output: Output, + non_inverting: IP, + output: OP, gain: Gain, - ) -> Pga; + ) -> Pga + where + IP: FrozenPin, + OP: FrozenPin; /// Trait for opamps that can be run in programmable gain mode, /// with external filtering. fn pga_external_filter< - B1: Borrow, - B2: Borrow<>::Vinm0>, + P1: FrozenPin, + P2: FrozenPin<>::Vinm0>, >( self, - non_inverting: B1, - filter: B2, + non_inverting: P1, + filter: P2, output: Output, gain: Gain, ) -> Pga; @@ -164,8 +172,8 @@ where /// Configures the opamp for programmable gain operation, with /// external filtering. fn pga_external_bias< - B1: Borrow, - B2: Borrow<>::Vinm0>, + B1: FrozenPin, + B2: FrozenPin<>::Vinm0>, >( self, non_inverting: B1, @@ -177,9 +185,9 @@ where /// Configures the opamp for programmable gain operation, with /// external filtering. fn pga_external_bias_and_filter< - B1: Borrow, - B2: Borrow<>::Vinm0>, - B3: Borrow<>::Vinm1>, + B1: FrozenPin, + B2: FrozenPin<>::Vinm0>, + B3: FrozenPin<>::Vinm1>, >( self, non_inverting: B1, @@ -209,7 +217,6 @@ where /// Configure the /// fn configure_pga( - output: Output, gain: Gain, mode: PgaMode, output_enable: bool, @@ -218,7 +225,7 @@ where Pga { opamp: PhantomData, non_inverting: PhantomData, - output, + output: PhantomData, } } } @@ -251,27 +258,21 @@ macro_rules! opamps { $opamp:ident => $opampreg:ident : { - vinm0: $vinm0:ty, - vinm1: $vinm1:ty, - inverting : { - $( - $inverting:ty - : - $inverting_mask:tt - ),* - $(,)? + vinm0: $vinm0:ty, + vinm1: $vinm1:ty, } , non_inverting : { $( - $non_inverting:ty - : $non_inverting_mask:tt + : + $non_inverting:ty + ),* $(,)? } @@ -366,41 +367,15 @@ macro_rules! opamps { } } - impl Follower<$opamp, Input, $output> { - /// Disables the opamp and returns the resources it held. - pub fn disable(self) -> (Disabled<$opamp>, Input, $output) { - unsafe { $opamp::_reset() }; - (Disabled { opamp: PhantomData }, self.input, self.output) - } - - /// Disables the external output. - /// This will connect the opamp output to the internal ADC. - /// If the output was enabled, the output pin is returned. - pub fn disable_output(self) -> (Follower<$opamp, Input, InternalOutput>, $output) { - unsafe { $opamp::_disable_output(); } - (Follower::<$opamp, Input, InternalOutput> { - opamp: PhantomData, - input: self.input, - output: InternalOutput, - }, self.output) - } - } - impl Follower<$opamp, Input, InternalOutput> { - /// Disables the opamp and returns the resources it held. - pub fn disable(self) -> (Disabled<$opamp>, Input) { - unsafe { $opamp::_reset() }; - (Disabled { opamp: PhantomData }, self.input) - } - /// Enables the external output pin. - pub fn enable_output(self, output:$output) -> Follower<$opamp, Input, $output> { + pub fn enable_output(self, _output: $output) -> Follower<$opamp, Input, $output> { unsafe { $opamp::_enable_output(); } Follower::<$opamp, Input, $output> { opamp: PhantomData, input: self.input, - output, + output: PhantomData, } } } @@ -415,43 +390,16 @@ macro_rules! opamps { } } - impl OpenLoop<$opamp, NonInverting, Inverting, $output> { - /// Disables the opamp and returns the resources it held. - pub fn disable(self) -> (Disabled<$opamp>, NonInverting, Inverting, $output) { - unsafe { $opamp::_reset() }; - (Disabled { opamp: PhantomData }, self.non_inverting, self.inverting, self.output) - } - - /// Disables the external output. - /// This will connect the opamp output to the internal ADC. - /// If the output was enabled, the output pin is returned. - pub fn disable_output(self) -> (OpenLoop<$opamp, NonInverting, Inverting, InternalOutput>, $output) { - unsafe { $opamp::_disable_output(); } - (OpenLoop::<$opamp, NonInverting, Inverting, InternalOutput> { - opamp: PhantomData, - inverting: self.inverting, - non_inverting: self.non_inverting, - output: InternalOutput, - }, self.output) - } - } - impl OpenLoop<$opamp, NonInverting, Inverting, InternalOutput> { - /// Disables the opamp and returns the resources it held. - pub fn disable(self) -> (Disabled<$opamp>, NonInverting, Inverting) { - unsafe { $opamp::_reset() }; - (Disabled { opamp: PhantomData }, self.non_inverting, self.inverting) - } - /// Enables the external output pin. - pub fn enable_output(self, output:$output) -> OpenLoop<$opamp, NonInverting, Inverting, $output> { + pub fn enable_output(self, _output:$output) -> OpenLoop<$opamp, NonInverting, Inverting, $output> { unsafe { $opamp::_enable_output(); } OpenLoop::<$opamp, NonInverting, Inverting, $output> { opamp: PhantomData, - inverting: self.inverting, - non_inverting: self.non_inverting, - output, + inverting: PhantomData, + non_inverting: PhantomData, + output: PhantomData, } } } @@ -466,25 +414,6 @@ macro_rules! opamps { } } - impl Pga<$opamp, NonInverting, $output> { - /// Disables the opamp and returns the resources it held. - pub fn disable(self) -> (Disabled<$opamp>, $output) { - unsafe { $opamp::_reset() }; - (Disabled { opamp: PhantomData }, self.output) - } - - /// Disables the external output. - /// This will connect the opamp output to the internal ADC. - pub fn disable_output(self) -> (Pga<$opamp, NonInverting, InternalOutput>, $output) { - unsafe { $opamp::_disable_output(); } - (Pga::<$opamp, NonInverting, InternalOutput> { - opamp: PhantomData, - non_inverting: self.non_inverting, - output: InternalOutput, - }, self.output) - } - } - impl Pga<$opamp, NonInverting, InternalOutput> { /// Disables the opamp and returns the resources it held. pub fn disable(self) -> Disabled<$opamp> { @@ -493,7 +422,7 @@ macro_rules! opamps { } /// Enables the external output pin. - pub fn enable_output(self, output: IntoOutput) -> Pga<$opamp, NonInverting, $output> + pub fn enable_output(self, _output: IntoOutput) -> Pga<$opamp, NonInverting, $output> where IntoOutput: Into<$output>, { @@ -502,13 +431,13 @@ macro_rules! opamps { Pga::<$opamp, NonInverting, $output> { opamp: PhantomData, non_inverting: self.non_inverting, - output: output.into(), + output: PhantomData, } } } opamps!{ @follower $opamp => $opampreg, $output, $($non_inverting_mask, $non_inverting),* } - opamps!{ @open_loop_tt $opamp => $opampreg, $output, $($non_inverting_mask, $non_inverting),* : ($($inverting_mask, $inverting),*) } + opamps!{ @open_loop_tt $opamp => $opampreg, $output, $($non_inverting_mask, $non_inverting),* : (vinm0, $vinm0, vinm1, $vinm1) } opamps!{ @pga_tt $opamp => $opampreg, $output, $($non_inverting_mask, $non_inverting),* : $vinm0, $vinm1 } )* @@ -555,31 +484,30 @@ macro_rules! opamps { } => { paste::paste!{ $( - impl IntoFollower <$opamp, IntoInput, IntoOutput, $input, $output> for Disabled<$opamp> + impl IntoFollower <$opamp, Input, IntoOutput, $input, $output> for Disabled<$opamp> where - IntoInput: Into<$input>, + Input: FrozenPin<$input>, IntoOutput: Into<$output>, { #[inline] fn follower( self, - input: IntoInput, + input: Input, output: IntoOutput, ) -> Follower<$opamp, $input, $output> { self.follower(input, InternalOutput).enable_output(output.into()) } } - impl IntoFollower <$opamp, IntoInput, InternalOutput, $input, InternalOutput> for Disabled<$opamp> + impl IntoFollower <$opamp, Input, InternalOutput, $input, InternalOutput> for Disabled<$opamp> where - IntoInput: Into<$input>, + Input: FrozenPin<$input>, { fn follower( self, - input: IntoInput, + _input: Input, _output: InternalOutput, ) -> Follower<$opamp, $input, InternalOutput> { - let input = input.into(); unsafe { use crate::stm32::opamp::[<$opampreg _csr>]::OPAINTOEN_A; (*crate::stm32::OPAMP::ptr()) @@ -596,7 +524,7 @@ macro_rules! opamps { .enabled() ); } - Follower {opamp: PhantomData, input, output: InternalOutput} + Follower {opamp: PhantomData, input: PhantomData, output: PhantomData} } } @@ -633,37 +561,35 @@ macro_rules! opamps { } => { paste::paste!{ $( - impl IntoOpenLoop - <$opamp, IntoNonInverting, IntoInverting, IntoOutput, $non_inverting, $inverting, $output> for Disabled<$opamp> + impl IntoOpenLoop + <$opamp, NonInverting, Inverting, IntoOutput, $non_inverting, $inverting, $output> for Disabled<$opamp> where - IntoNonInverting: Into<$non_inverting>, - IntoInverting: Into<$inverting>, + NonInverting: FrozenPin<$non_inverting>, + Inverting: FrozenPin<$inverting>, IntoOutput: Into<$output>, { #[inline] fn open_loop( self, - non_inverting: IntoNonInverting, - inverting: IntoInverting, + non_inverting: NonInverting, + inverting: Inverting, output: IntoOutput, ) -> OpenLoop<$opamp, $non_inverting, $inverting, $output> { self.open_loop(non_inverting, inverting, InternalOutput).enable_output(output.into()) } } - impl IntoOpenLoop - <$opamp, IntoNonInverting, IntoInverting, InternalOutput, $non_inverting, $inverting, InternalOutput> for Disabled<$opamp> + impl IntoOpenLoop + <$opamp, NonInverting, Inverting, InternalOutput, $non_inverting, $inverting, InternalOutput> for Disabled<$opamp> where - IntoNonInverting: Into<$non_inverting>, - IntoInverting: Into<$inverting>, + NonInverting: FrozenPin<$non_inverting>, + Inverting: FrozenPin<$inverting>, { fn open_loop( self, - non_inverting: IntoNonInverting, - inverting: IntoInverting, + _non_inverting: NonInverting, + _inverting: Inverting, _output: InternalOutput, ) -> OpenLoop<$opamp, $non_inverting, $inverting, InternalOutput> { - let non_inverting = non_inverting.into(); - let inverting = inverting.into(); unsafe { use crate::stm32::opamp::[<$opampreg _csr>]::OPAINTOEN_A; (*crate::stm32::OPAMP::ptr()) @@ -679,7 +605,7 @@ macro_rules! opamps { .enabled() ); } - OpenLoop {opamp: PhantomData, non_inverting, inverting, output: InternalOutput} + OpenLoop {opamp: PhantomData, non_inverting: PhantomData, inverting: PhantomData, output: PhantomData } } } )* @@ -749,115 +675,121 @@ macro_rules! opamps { impl IntoPga<$opamp, $non_inverting, $output> for Disabled<$opamp> { - fn pga>( + fn pga( self, - _non_inverting: B, - output: $output, + _non_inverting: IP, + _output: OP, gain: Gain, ) -> Pga<$opamp, $non_inverting, $output> + where + IP: FrozenPin<$non_inverting>, + OP: FrozenPin<$output>, { - $opamp::configure_pga(output.into(), gain, PgaMode::Pga, true) + $opamp::configure_pga(gain, PgaMode::Pga, true) } #[allow(private_bounds)] fn pga_external_filter< - B1: Borrow<$non_inverting>, - B2: Borrow<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm0>, + P1: FrozenPin<$non_inverting>, + P2: FrozenPin<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm0>, >( self, - _non_inverting: B1, - _filter: B2, - output: $output, + _non_inverting: P1, + _filter: P2, + _output: $output, gain: Gain, ) -> Pga<$opamp, $non_inverting, $output> { - $opamp::configure_pga(output.into(), gain, PgaMode::PgaExternalFilter, true) + $opamp::configure_pga(gain, PgaMode::PgaExternalFilter, true) } #[allow(private_bounds)] fn pga_external_bias< - B1: Borrow<$non_inverting>, - B2: Borrow<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm0>, + P1: FrozenPin<$non_inverting>, + P2: FrozenPin<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm0>, >( self, - _non_inverting: B1, - _inverting: B2, - output: $output, + _non_inverting: P1, + _inverting: P2, + _output: $output, gain: Gain, ) -> Pga<$opamp, $non_inverting, $output> { - $opamp::configure_pga(output.into(), gain, PgaMode::PgaExternalBias, true) + $opamp::configure_pga(gain, PgaMode::PgaExternalBias, true) } #[allow(private_bounds)] fn pga_external_bias_and_filter< - B1: Borrow<$non_inverting>, - B2: Borrow<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm0>, - B3: Borrow<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm1>, + P1: FrozenPin<$non_inverting>, + P2: FrozenPin<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm0>, + P3: FrozenPin<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm1>, >( self, - _non_inverting: B1, - _inverting: B2, - _filter: B3, - output: $output, + _non_inverting: P1, + _inverting: P2, + _filter: P3, + _output: $output, gain: Gain, ) -> Pga<$opamp, $non_inverting, $output> { - $opamp::configure_pga(output.into(), gain, PgaMode::PgaExternalBiasAndFilter, true) + $opamp::configure_pga(gain, PgaMode::PgaExternalBiasAndFilter, true) } } impl IntoPga<$opamp, $non_inverting, InternalOutput> for Disabled<$opamp> { - fn pga>( + fn pga( self, - _non_inverting: B, - _output: InternalOutput, + _non_inverting: IP, + _output: OP, gain: Gain, ) -> Pga<$opamp, $non_inverting, InternalOutput> + where + IP: FrozenPin<$non_inverting>, + OP: FrozenPin { - $opamp::configure_pga(InternalOutput, gain, PgaMode::Pga, true) + $opamp::configure_pga(gain, PgaMode::Pga, true) } #[allow(private_bounds)] fn pga_external_filter< - B1: Borrow<$non_inverting>, - B2: Borrow<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm0>, + P1: FrozenPin<$non_inverting>, + P2: FrozenPin<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm0>, >( self, - _non_inverting: B1, - _filter: B2, + _non_inverting: P1, + _filter: P2, _output: InternalOutput, gain: Gain, ) -> Pga<$opamp, $non_inverting, InternalOutput> { - $opamp::configure_pga(InternalOutput, gain, PgaMode::PgaExternalFilter, true) + $opamp::configure_pga(gain, PgaMode::PgaExternalFilter, true) } #[allow(private_bounds)] fn pga_external_bias< - B1: Borrow<$non_inverting>, - B2: Borrow<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm0>, + P1: FrozenPin<$non_inverting>, + P2: FrozenPin<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm0>, >( self, - _non_inverting: B1, - _inverting: B2, + _non_inverting: P1, + _inverting: P2, _output: InternalOutput, gain: Gain, ) -> Pga<$opamp, $non_inverting, InternalOutput> { - $opamp::configure_pga(InternalOutput, gain, PgaMode::PgaExternalBias, true) + $opamp::configure_pga(gain, PgaMode::PgaExternalBias, true) } #[allow(private_bounds)] fn pga_external_bias_and_filter< - B1: Borrow<$non_inverting>, - B2: Borrow<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm0>, - B3: Borrow<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm1>, + P1: FrozenPin<$non_inverting>, + P2: FrozenPin<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm0>, + P3: FrozenPin<<$opamp as ConfigurePgaReg<$opamp, $non_inverting>>::Vinm1>, >( self, - _non_inverting: B1, - _inverting: B2, - _filter: B3, + _non_inverting: P1, + _inverting: P2, + _filter: P3, _output: InternalOutput, gain: Gain, ) -> Pga<$opamp, $non_inverting, InternalOutput> { - $opamp::configure_pga(InternalOutput, gain, PgaMode::PgaExternalBiasAndFilter, true) + $opamp::configure_pga(gain, PgaMode::PgaExternalBiasAndFilter, true) } } } @@ -867,47 +799,47 @@ macro_rules! opamps { #[cfg(any(feature = "stm32g431", feature = "stm32g441", feature = "stm32g471",))] opamps! { Opamp1 => opamp1: { - vinm0: crate::gpio::gpioa::PA3, - vinm1: crate::gpio::gpioc::PC5, + vinm0: PA3, + vinm1: PC5, inverting: { - crate::gpio::gpioa::PA3: vinm0, - crate::gpio::gpioc::PC5: vinm1, + vinm0: PA3, + vinm1: PC5, }, non_inverting: { - crate::gpio::gpioa::PA1: vinp0, - crate::gpio::gpioa::PA3: vinp1, - crate::gpio::gpioa::PA7: vinp2, + vinp0: PA1, + vinp1: PA3, + vinp2: PA7, }, - output: crate::gpio::gpioa::PA2, + output: PA2, }, Opamp2 => opamp2: { - vinm0: crate::gpio::gpioa::PA5, - vinm1: crate::gpio::gpioc::PC5, + vinm0: PA5, + vinm1: PC5, inverting: { - crate::gpio::gpioa::PA5: vinm0, - crate::gpio::gpioc::PC5: vinm1, + vinm0: PA5, + vinm1: PC5, }, non_inverting: { - crate::gpio::gpioa::PA7: vinp0, - crate::gpio::gpiob::PB14: vinp1, - crate::gpio::gpiob::PB0: vinp2, - crate::gpio::gpiod::PD14: vinp3, + vinp0: PA7, + vinp1: PB14, + vinp2: PB0, + vinp3: PD14, }, - output: crate::gpio::gpioa::PA6, + output: PA6, }, Opamp3 => opamp3: { - vinm0: crate::gpio::gpiob::PB2, - vinm1: crate::gpio::gpiob::PB10, + vinm0: PB2, + vinm1: PB10, inverting: { - crate::gpio::gpiob::PB2: vinm0, - crate::gpio::gpiob::PB10: vinm1, + vinm0: PB2, + vinm1: PB10, }, non_inverting: { - crate::gpio::gpiob::PB0: vinp0, - crate::gpio::gpiob::PB13: vinp1, - crate::gpio::gpioa::PA1: vinp2, + vinp0: PB0, + vinp1: PB13, + vinp2: PA1, }, - output: crate::gpio::gpiob::PB1, + output: PB1, }, } @@ -919,88 +851,76 @@ opamps! { ))] opamps! { Opamp1 => opamp1: { - vinm0: crate::gpio::gpioa::PA3, - vinm1: crate::gpio::gpioc::PC5, inverting: { - crate::gpio::gpioa::PA3: vinm0, - crate::gpio::gpioc::PC5: vinm1, + vinm0: PA3, + vinm1: PC5, }, non_inverting: { - crate::gpio::gpioa::PA1: vinp0, - crate::gpio::gpioa::PA3: vinp1, - crate::gpio::gpioa::PA7: vinp2, + vinp0: PA1, + vinp1: PA3, + vinp2: PA7 }, - output: crate::gpio::gpioa::PA2, + output: PA2, }, Opamp2 => opamp2: { - vinm0: crate::gpio::gpioa::PA5, - vinm1: crate::gpio::gpioc::PC5, inverting: { - crate::gpio::gpioa::PA5: vinm0, - crate::gpio::gpioc::PC5: vinm1, + vinm0: PA5, + vinm1: PC5, }, non_inverting: { - crate::gpio::gpioa::PA7: vinp0, - crate::gpio::gpiob::PB14: vinp1, - crate::gpio::gpiob::PB0: vinp2, - crate::gpio::gpiod::PD14: vinp3, + vinp0: PA7, + vinp1: PB14, + vinp2: PB0, + vinp3: PD14, }, - output: crate::gpio::gpioa::PA6, + output: PA6, }, Opamp3 => opamp3: { - vinm0: crate::gpio::gpiob::PB2, - vinm1: crate::gpio::gpiob::PB10, inverting: { - crate::gpio::gpiob::PB2: vinm0, - crate::gpio::gpiob::PB10: vinm1, + vinm0: PB2, + vinm1: PB10, }, non_inverting: { - crate::gpio::gpiob::PB0: vinp0, - crate::gpio::gpiob::PB13: vinp1, - crate::gpio::gpioa::PA1: vinp2, + vinp0: PB0, + vinp1: PB13, + vinp2: PA1, }, - output: crate::gpio::gpiob::PB1, + output: PB1, }, Opamp4 => opamp4: { - vinm0: crate::gpio::gpiob::PB10, - vinm1: crate::gpio::gpiod::PD8, inverting: { - crate::gpio::gpiob::PB10: vinm0, - crate::gpio::gpiod::PD8: vinm1, + vinm0: PB10, + vinm1: PD8, }, non_inverting: { - crate::gpio::gpiob::PB13: vinp0, - crate::gpio::gpiod::PD11: vinp1, - crate::gpio::gpiob::PB11: vinp2, + vinp0: PB13, + vinp1: PD11, + vinp2: PB11, }, - output: crate::gpio::gpiob::PB12, + output: PB12, }, Opamp5 => opamp5: { - vinm0: crate::gpio::gpiob::PB15, - vinm1: crate::gpio::gpioa::PA3, inverting: { - crate::gpio::gpiob::PB15: vinm0, - crate::gpio::gpioa::PA3: vinm1, + vinm0: PB15, + vinm1: PA3, }, non_inverting: { - crate::gpio::gpiob::PB14: vinp0, - crate::gpio::gpiod::PD12: vinp1, - crate::gpio::gpioc::PC3: vinp2, + vinp0: PB14, + vinp1: PD12, + vinp2: PC3, }, - output: crate::gpio::gpioa::PA8, + output: PA8, }, Opamp6 => opamp6: { - vinm0: crate::gpio::gpioa::PA1, - vinm1: crate::gpio::gpiob::PB1, inverting: { - crate::gpio::gpioa::PA1: vinm0, - crate::gpio::gpiob::PB1: vinm1, + vinm0: PA1, + vinm1: PB1, }, non_inverting: { - crate::gpio::gpiob::PB12: vinp0, - crate::gpio::gpiod::PD9: vinp1, - crate::gpio::gpiob::PB13: vinp2, + vinp0: PB12, + vinp1: PD9, + vinp2: PB13, }, - output: crate::gpio::gpiob::PB11, + output: PB11, }, } diff --git a/src/pwm.rs b/src/pwm.rs index 5f27211d..774221f1 100644 --- a/src/pwm.rs +++ b/src/pwm.rs @@ -172,6 +172,8 @@ use core::marker::PhantomData; use core::mem::MaybeUninit; +use crate::gpio::FrozenPin; +use crate::gpio::IsFrozen; use crate::hal; use crate::stm32::LPTIMER1; use crate::stm32::RCC; @@ -219,7 +221,7 @@ use crate::gpio::{Alternate, AF1, AF10, AF11, AF12, AF2, AF3, AF4, AF5, AF6, AF9 // This trait marks that a GPIO pin can be used with a specific timer channel // TIM is the timer being used // CHANNEL is a marker struct for the channel (or multi channels for tuples) -// Example: impl Pins for PA8> { type Channel = Pwm; } +// Example: impl Pins for PA8, IsFrozen> { type Channel = Pwm; } /// Pins is a trait that marks which GPIO pins may be used as PWM channels; it should not be directly used. /// See the device datasheet 'Pin descriptions' chapter for which pins can be used with which timer PWM channels (or look at Implementors) pub trait Pins { @@ -550,27 +552,27 @@ macro_rules! pins { pins! { LPTIMER1: OUT: [ - PA14>, - PB2>, - PC1> + PA14, IsFrozen>, + PB2, IsFrozen>, + PC1, IsFrozen> ] } // Dual channel timers pins! { TIM15: CH1(ComplementaryDisabled): [ - PA2>, - PB14>, - PF9> + PA2, IsFrozen>, + PB14, IsFrozen>, + PF9, IsFrozen> ] CH2(ComplementaryImpossible): [ - PA3>, - PB15>, - PF10> + PA3, IsFrozen>, + PB15, IsFrozen>, + PF10, IsFrozen> ] CH1N: [ - PA1>, - PB15>, + PA1, IsFrozen>, + PB15, IsFrozen>, #[cfg(any( feature = "stm32g471", feature = "stm32g473", @@ -578,47 +580,47 @@ pins! { feature = "stm32g483", feature = "stm32g484" ))] - PG9> + PG9, IsFrozen> ] CH2N: [] BRK: [ - PA9>, - PC5> + PA9, IsFrozen>, + PC5, IsFrozen> ] BRK2: [] TIM16: CH1(ComplementaryDisabled): [ - PA6>, - PA12>, - PB4>, - PB8>, - PE0> + PA6, IsFrozen>, + PA12, IsFrozen>, + PB4, IsFrozen>, + PB8, IsFrozen>, + PE0, IsFrozen> ] CH2(ComplementaryImpossible): [] CH1N: [ - PA13>, - PB6> + PA13, IsFrozen>, + PB6, IsFrozen> ] CH2N: [] BRK: [ - PB5> + PB5, IsFrozen> ] BRK2: [] TIM17: CH1(ComplementaryDisabled): [ - PA7>, - PB5>, - PB9>, - PE1> + PA7, IsFrozen>, + PB5, IsFrozen>, + PB9, IsFrozen>, + PE1, IsFrozen> ] CH2(ComplementaryImpossible): [] CH1N: [ - PB7> + PB7, IsFrozen> ] CH2N: [] BRK: [ - PA10>, - PB4> + PA10, IsFrozen>, + PB4, IsFrozen> ] BRK2: [] } @@ -626,87 +628,87 @@ pins! { pins! { TIM1: CH1(ComplementaryDisabled): [ - PA8>, - PC0>, - PE9> + PA8, IsFrozen>, + PC0, IsFrozen>, + PE9, IsFrozen> ] CH2(ComplementaryDisabled): [ - PA9>, - PC1>, - PE11> + PA9, IsFrozen>, + PC1, IsFrozen>, + PE11, IsFrozen> ] CH3(ComplementaryDisabled): [ - PA10>, - PC2>, - PE13> + PA10, IsFrozen>, + PC2, IsFrozen>, + PE13, IsFrozen> ] CH4(ComplementaryDisabled): [ - PA11>, - PC3>, - PE14> + PA11, IsFrozen>, + PC3, IsFrozen>, + PE14, IsFrozen> ] CH1N: [ - PA7>, - PA11>, - PB13>, - PC13>, - PE8> + PA7, IsFrozen>, + PA11, IsFrozen>, + PB13, IsFrozen>, + PC13, IsFrozen>, + PE8, IsFrozen> ] CH2N: [ - PA12>, - PB0>, - PB14>, - PE10> + PA12, IsFrozen>, + PB0, IsFrozen>, + PB14, IsFrozen>, + PE10, IsFrozen> ] CH3N: [ - PB1>, - PB9>, - PB15>, - PE12>, - PF0> + PB1, IsFrozen>, + PB9, IsFrozen>, + PB15, IsFrozen>, + PE12, IsFrozen>, + PF0, IsFrozen> ] CH4N: [ - PC5>, - PE15> + PC5, IsFrozen>, + PE15, IsFrozen> ] BRK: [ - PA6>, - PA14>, - PA15>, - PB8>, - PB10>, - PB12>, - PC13>, - PE15> + PA6, IsFrozen>, + PA14, IsFrozen>, + PA15, IsFrozen>, + PB8, IsFrozen>, + PB10, IsFrozen>, + PB12, IsFrozen>, + PC13, IsFrozen>, + PE15, IsFrozen> ] BRK2: [ - PA11>, - PC3>, - PE14> + PA11, IsFrozen>, + PC3, IsFrozen>, + PE14, IsFrozen> ] TIM2: CH1(ComplementaryImpossible): [ - PA0>, - PA5>, - PA15>, - PD3> + PA0, IsFrozen>, + PA5, IsFrozen>, + PA15, IsFrozen>, + PD3, IsFrozen> ] CH2(ComplementaryImpossible): [ - PA1>, - PB3>, - PD4> + PA1, IsFrozen>, + PB3, IsFrozen>, + PD4, IsFrozen> ] CH3(ComplementaryImpossible): [ - PA2>, - PA9>, - PB10>, - PD7> + PA2, IsFrozen>, + PA9, IsFrozen>, + PB10, IsFrozen>, + PD7, IsFrozen> ] CH4(ComplementaryImpossible): [ - PA3>, - PA10>, - PB11>, - PD6> + PA3, IsFrozen>, + PA10, IsFrozen>, + PB11, IsFrozen>, + PD6, IsFrozen> ] CH1N: [] CH2N: [] @@ -716,28 +718,28 @@ pins! { BRK2: [] TIM3: CH1(ComplementaryImpossible): [ - PA6>, - PB4>, - PC6>, - PE2> + PA6, IsFrozen>, + PB4, IsFrozen>, + PC6, IsFrozen>, + PE2, IsFrozen> ] CH2(ComplementaryImpossible): [ - PA4>, - PA7>, - PB5>, - PC7>, - PE3> + PA4, IsFrozen>, + PA7, IsFrozen>, + PB5, IsFrozen>, + PC7, IsFrozen>, + PE3, IsFrozen> ] CH3(ComplementaryImpossible): [ - PB0>, - PC8>, - PE4> + PB0, IsFrozen>, + PC8, IsFrozen>, + PE4, IsFrozen> ] CH4(ComplementaryImpossible): [ - PB1>, - PB7>, - PC9>, - PE5> + PB1, IsFrozen>, + PB7, IsFrozen>, + PC9, IsFrozen>, + PE5, IsFrozen> ] CH1N: [] CH2N: [] @@ -747,23 +749,23 @@ pins! { BRK2: [] TIM4: CH1(ComplementaryImpossible): [ - PA11>, - PB6>, - PD12> + PA11, IsFrozen>, + PB6, IsFrozen>, + PD12, IsFrozen> ] CH2(ComplementaryImpossible): [ - PA12>, - PB7>, - PD13> + PA12, IsFrozen>, + PB7, IsFrozen>, + PD13, IsFrozen> ] CH3(ComplementaryImpossible): [ - PA13>, - PB8>, - PD14> + PA13, IsFrozen>, + PB8, IsFrozen>, + PD14, IsFrozen> ] CH4(ComplementaryImpossible): [ - PB9>, - PD15>, + PB9, IsFrozen>, + PD15, IsFrozen>, #[cfg(any( feature = "stm32g471", feature = "stm32g473", @@ -771,7 +773,7 @@ pins! { feature = "stm32g483", feature = "stm32g484" ))] - PF6> + PF6, IsFrozen> ] CH1N: [] CH2N: [] @@ -790,24 +792,24 @@ pins! { pins! { TIM5: CH1(ComplementaryImpossible): [ - PA0>, - PB2>, - PF6> + PA0, IsFrozen>, + PB2, IsFrozen>, + PF6, IsFrozen> ] CH2(ComplementaryImpossible): [ - PA1>, - PC12>, - PF7> + PA1, IsFrozen>, + PC12, IsFrozen>, + PF7, IsFrozen> ] CH3(ComplementaryImpossible): [ - PA2>, - PE8>, - PF8> + PA2, IsFrozen>, + PE8, IsFrozen>, + PF8, IsFrozen> ] CH4(ComplementaryImpossible): [ - PA3>, - PE9>, - PF9> + PA3, IsFrozen>, + PE9, IsFrozen>, + PF9, IsFrozen> ] CH1N: [] CH2N: [] @@ -819,53 +821,53 @@ pins! { pins! { TIM8: CH1(ComplementaryDisabled): [ - PA15>, - PB6>, - PC6> + PA15, IsFrozen>, + PB6, IsFrozen>, + PC6, IsFrozen> ] CH2(ComplementaryDisabled): [ - PA14>, - PB8>, - PC7> + PA14, IsFrozen>, + PB8, IsFrozen>, + PC7, IsFrozen> ] CH3(ComplementaryDisabled): [ - PB9>, - PC8> + PB9, IsFrozen>, + PC8, IsFrozen> ] CH4(ComplementaryDisabled): [ - PC9>, - PD1> + PC9, IsFrozen>, + PD1, IsFrozen> ] CH1N: [ - PA7>, - PB3>, - PC10> + PA7, IsFrozen>, + PB3, IsFrozen>, + PC10, IsFrozen> ] CH2N: [ - PB0>, - PB4>, - PC11> + PB0, IsFrozen>, + PB4, IsFrozen>, + PC11, IsFrozen> ] CH3N: [ - PB1>, - PB5>, - PC12> + PB1, IsFrozen>, + PB5, IsFrozen>, + PC12, IsFrozen> ] CH4N: [ - PC13>, - PD0> + PC13, IsFrozen>, + PD0, IsFrozen> ] BRK: [ - PA0>, - PA6>, - PA10>, - PB7>, - PD2> + PA0, IsFrozen>, + PA6, IsFrozen>, + PA10, IsFrozen>, + PB7, IsFrozen>, + PD2, IsFrozen> ] BRK2: [ - PB6>, - PC9>, - PD1> + PB6, IsFrozen>, + PC9, IsFrozen>, + PD1, IsFrozen> ] } #[cfg(any( @@ -879,108 +881,108 @@ pins! { pins! { TIM20: CH1(ComplementaryDisabled): [ - PB2>, - PE2>, + PB2, IsFrozen>, + PE2, IsFrozen>, #[cfg(any( feature = "stm32g473", feature = "stm32g474", feature = "stm32g483", feature = "stm32g484", ))] - PF12> + PF12, IsFrozen> ] CH2(ComplementaryDisabled): [ - PC2>, - PE3>, + PC2, IsFrozen>, + PE3, IsFrozen>, #[cfg(any( feature = "stm32g473", feature = "stm32g474", feature = "stm32g483", feature = "stm32g484", ))] - PF13> + PF13, IsFrozen> ] CH3(ComplementaryDisabled): [ - PC8>, - PF2>, + PC8, IsFrozen>, + PF2, IsFrozen>, #[cfg(any( feature = "stm32g473", feature = "stm32g474", feature = "stm32g483", feature = "stm32g484", ))] - PF14> + PF14, IsFrozen> ] CH4(ComplementaryDisabled): [ - PE1>, + PE1, IsFrozen>, #[cfg(any( feature = "stm32g473", feature = "stm32g474", feature = "stm32g483", feature = "stm32g484", ))] - PF3>, + PF3, IsFrozen>, #[cfg(any( feature = "stm32g473", feature = "stm32g474", feature = "stm32g483", feature = "stm32g484", ))] - PF15> + PF15, IsFrozen> ] CH1N: [ - PE4>, + PE4, IsFrozen>, #[cfg(any( feature = "stm32g473", feature = "stm32g474", feature = "stm32g483", feature = "stm32g484", ))] - PF4>, + PF4, IsFrozen>, #[cfg(any( feature = "stm32g473", feature = "stm32g474", feature = "stm32g483", feature = "stm32g484", ))] - PG0> + PG0, IsFrozen> ] CH2N: [ - PE5>, + PE5, IsFrozen>, #[cfg(any( feature = "stm32g473", feature = "stm32g474", feature = "stm32g483", feature = "stm32g484", ))] - PF5>, + PF5, IsFrozen>, #[cfg(any( feature = "stm32g473", feature = "stm32g474", feature = "stm32g483", feature = "stm32g484", ))] - PG1> + PG1, IsFrozen> ] CH3N: [ - PE6>, + PE6, IsFrozen>, #[cfg(any( feature = "stm32g473", feature = "stm32g474", feature = "stm32g483", feature = "stm32g484", ))] - PG2> + PG2, IsFrozen> ] CH4N: [ - PE0>, + PE0, IsFrozen>, #[cfg(any( feature = "stm32g473", feature = "stm32g474", feature = "stm32g483", feature = "stm32g484", ))] - PG3> + PG3, IsFrozen> ] BRK: [ #[cfg(any( @@ -989,22 +991,22 @@ pins! { feature = "stm32g483", feature = "stm32g484", ))] - PF7>, - PF9>, + PF7, IsFrozen>, + PF9, IsFrozen>, #[cfg(any( feature = "stm32g473", feature = "stm32g474", feature = "stm32g483", feature = "stm32g484", ))] - PG3>, + PG3, IsFrozen>, #[cfg(any( feature = "stm32g473", feature = "stm32g474", feature = "stm32g483", feature = "stm32g484", ))] - PG6> + PG6, IsFrozen> ] BRK2: [ #[cfg(any( @@ -1013,15 +1015,15 @@ pins! { feature = "stm32g483", feature = "stm32g484", ))] - PF8>, - PF10>, + PF8, IsFrozen>, + PF10, IsFrozen>, #[cfg(any( feature = "stm32g473", feature = "stm32g474", feature = "stm32g483", feature = "stm32g484", ))] - PG4> + PG4, IsFrozen> ] } @@ -1112,19 +1114,21 @@ fn calculate_deadtime(base_freq: Hertz, deadtime: NanoSecond) -> (u8, u8) { /// Allows the pwm() method to be added to the peripheral register structs from the device crate pub trait PwmExt: Sized { /// The requested frequency will be rounded to the nearest achievable frequency; the actual frequency may be higher or lower than requested. - fn pwm(self, _pins: PINS, frequency: T, rcc: &mut Rcc) -> PINS::Channel + fn pwm(self, _pins: P, frequency: T, rcc: &mut Rcc) -> PINS::Channel where + P: FrozenPin, PINS: Pins, T: Into; } pub trait PwmAdvExt: Sized { - fn pwm_advanced( + fn pwm_advanced( self, - _pins: PINS, + _pins: P, rcc: &mut Rcc, ) -> PwmBuilder where + P: FrozenPin, PINS: Pins; } @@ -1132,8 +1136,9 @@ pub trait PwmAdvExt: Sized { macro_rules! pwm_ext_hal { ($TIMX:ident: $timX:ident) => { impl PwmExt for $TIMX { - fn pwm(self, pins: PINS, frequency: T, rcc: &mut Rcc) -> PINS::Channel + fn pwm(self, pins: P, frequency: T, rcc: &mut Rcc) -> PINS::Channel where + P: FrozenPin, PINS: Pins, T: Into, { @@ -1151,13 +1156,14 @@ macro_rules! tim_hal { pwm_ext_hal!($TIMX: $timX); /// Configures PWM - fn $timX( + fn $timX( tim: $TIMX, - _pins: PINS, + _pins: P, freq: Hertz, rcc: &mut Rcc, ) -> PINS::Channel where + P: FrozenPin, PINS: Pins<$TIMX, T, U>, { unsafe { @@ -1194,12 +1200,13 @@ macro_rules! tim_hal { } impl PwmAdvExt<$typ> for $TIMX { - fn pwm_advanced( + fn pwm_advanced( self, - _pins: PINS, + _pins: P, rcc: &mut Rcc, ) -> PwmBuilder where + P: FrozenPin, PINS: Pins { unsafe { @@ -1769,13 +1776,14 @@ macro_rules! lptim_hal { pwm_ext_hal!($TIMX: $timX); /// Configures PWM signal on the LPTIM OUT pin. - fn $timX( + fn $timX( tim: $TIMX, - _pins: PINS, + _pins: P, freq: Hertz, rcc: &mut Rcc, ) -> PINS::Channel where + P: FrozenPin, PINS: Pins<$TIMX, T, U>, { unsafe {