diff --git a/examples/embassy/Cargo.toml b/examples/embassy/Cargo.toml index fdde545..717adab 100644 --- a/examples/embassy/Cargo.toml +++ b/examples/embassy/Cargo.toml @@ -8,6 +8,7 @@ cfg-if = "1" cortex-m = { version = "0.7", features = ["critical-section-single-core"] } cortex-m-rt = "0.7" embedded-hal = "1" +embedded-hal-async = "1" rtt-target = "0.6" panic-rtt-target = "0.2" diff --git a/examples/embassy/src/bin/async-gpio.rs b/examples/embassy/src/bin/async-gpio.rs new file mode 100644 index 0000000..2ec3bfe --- /dev/null +++ b/examples/embassy/src/bin/async-gpio.rs @@ -0,0 +1,181 @@ +#![no_std] +#![no_main] + +use embassy_executor::Spawner; +use embassy_sync::{blocking_mutex::raw::ThreadModeRawMutex, channel::Channel}; +use embassy_time::{Duration, Instant, Timer}; +use embedded_hal::digital::{InputPin, OutputPin, StatefulOutputPin}; +use panic_rtt_target as _; +use rtt_target::{rprintln, rtt_init_print}; +use va108xx_embassy::embassy; +use va108xx_hal::gpio::{handle_interrupt_for_async_gpio, InputPinAsync}; +use va108xx_hal::{ + gpio::{DynPin, PinsA}, + pac::{self, interrupt}, + prelude::*, +}; + +const SYSCLK_FREQ: Hertz = Hertz::from_raw(50_000_000); + +#[derive(Clone, Copy)] +pub struct GpioCmd { + cmd_type: GpioCmdType, + after_delay: u32, +} + +impl GpioCmd { + pub fn new(cmd_type: GpioCmdType, after_delay: u32) -> Self { + Self { + cmd_type, + after_delay, + } + } +} + +#[derive(Clone, Copy)] +pub enum GpioCmdType { + SetHigh, + SetLow, + RisingEdge, + FallingEdge, +} + +// Declare a bounded channel of 3 u32s. +static CHANNEL: Channel = Channel::new(); + +#[embassy_executor::main] +async fn main(spawner: Spawner) { + rtt_init_print!(); + rprintln!("-- VA108xx Async GPIO Demo --"); + + let mut dp = pac::Peripherals::take().unwrap(); + + // Safety: Only called once here. + unsafe { + embassy::init( + &mut dp.sysconfig, + &dp.irqsel, + SYSCLK_FREQ, + dp.tim23, + dp.tim22, + ) + }; + + let porta = PinsA::new(&mut dp.sysconfig, Some(dp.ioconfig), dp.porta); + let led0 = porta.pa10.into_readable_push_pull_output(); + let out = porta.pa0.into_readable_push_pull_output(); + let input = porta.pa1.into_floating_input(); + let mut async_input = InputPinAsync::new(input, pac::Interrupt::OC10); + let out_dyn = out.downgrade(); + let mut led_0_dyn = led0.downgrade(); + + spawner.spawn(output_task(out_dyn)).unwrap(); + rprintln!( + "sending SetHigh command ({} ms)", + Instant::now().as_millis() + ); + CHANNEL.send(GpioCmd::new(GpioCmdType::SetHigh, 20)).await; + async_input.wait_for_high().await; + rprintln!("Input pin is high now ({} ms)", Instant::now().as_millis()); + + rprintln!("sending SetLow command ({} ms)", Instant::now().as_millis()); + CHANNEL.send(GpioCmd::new(GpioCmdType::SetLow, 20)).await; + async_input.wait_for_low().await; + rprintln!("Input pin is low now ({} ms)", Instant::now().as_millis()); + + rprintln!( + "sending RisingEdge command ({} ms)", + Instant::now().as_millis() + ); + CHANNEL + .send(GpioCmd::new(GpioCmdType::RisingEdge, 20)) + .await; + async_input.wait_for_rising_edge().await; + rprintln!( + "input pin had rising edge ({} ms)", + Instant::now().as_millis() + ); + + rprintln!( + "sending Falling command ({} ms)", + Instant::now().as_millis() + ); + CHANNEL + .send(GpioCmd::new(GpioCmdType::FallingEdge, 20)) + .await; + async_input.wait_for_falling_edge().await; + rprintln!( + "input pin had a falling edge ({} ms)", + Instant::now().as_millis() + ); + + rprintln!( + "sending Falling command ({} ms)", + Instant::now().as_millis() + ); + CHANNEL + .send(GpioCmd::new(GpioCmdType::FallingEdge, 20)) + .await; + async_input.wait_for_any_edge().await; + rprintln!( + "input pin had a falling (any) edge ({} ms)", + Instant::now().as_millis() + ); + + rprintln!( + "sending Falling command ({} ms)", + Instant::now().as_millis() + ); + CHANNEL + .send(GpioCmd::new(GpioCmdType::RisingEdge, 20)) + .await; + async_input.wait_for_any_edge().await; + rprintln!( + "input pin had a rising (any) edge ({} ms)", + Instant::now().as_millis() + ); + + rprintln!("Example done, toggling LED0"); + loop { + led_0_dyn.toggle().unwrap(); + Timer::after(Duration::from_millis(500)).await; + } +} + +#[embassy_executor::task] +async fn output_task(mut out: DynPin) { + loop { + let next_cmd = CHANNEL.receive().await; + Timer::after(Duration::from_millis(next_cmd.after_delay.into())).await; + match next_cmd.cmd_type { + GpioCmdType::SetHigh => { + rprintln!("Set output high"); + out.set_high().unwrap(); + } + GpioCmdType::SetLow => { + rprintln!("Set output low"); + out.set_low().unwrap(); + } + GpioCmdType::RisingEdge => { + if !out.is_low().unwrap() { + out.set_low().unwrap(); + } + rprintln!("Rising edge"); + out.set_high().unwrap(); + } + GpioCmdType::FallingEdge => { + if !out.is_high().unwrap() { + out.set_high().unwrap(); + } + rprintln!("Falling edge"); + out.set_low().unwrap(); + } + } + } +} + +#[interrupt] +#[allow(non_snake_case)] +fn OC10() { + handle_interrupt_for_async_gpio(); +} diff --git a/va108xx-hal/Cargo.toml b/va108xx-hal/Cargo.toml index 3ad52c9..c560267 100644 --- a/va108xx-hal/Cargo.toml +++ b/va108xx-hal/Cargo.toml @@ -16,6 +16,7 @@ cortex-m-rt = "0.7" nb = "1" paste = "1" embedded-hal = "1" +embedded-hal-async = "1" embedded-hal-nb = "1" embedded-io = "0.6" fugit = "0.3" @@ -25,6 +26,8 @@ delegate = ">=0.12, <=0.13" void = { version = "1", default-features = false } once_cell = {version = "1", default-features = false } va108xx = { version = "0.3", default-features = false, features = ["critical-section"]} +portable-atomic = { version = "1", features = ["unsafe-assume-single-core"]} +embassy-sync = "0.6" defmt = { version = "0.3", optional = true } diff --git a/va108xx-hal/docs.sh b/va108xx-hal/docs.sh new file mode 100755 index 0000000..37563d2 --- /dev/null +++ b/va108xx-hal/docs.sh @@ -0,0 +1,3 @@ +#!/bin/sh +export RUSTDOCFLAGS="--cfg docsrs --generate-link-to-definition -Z unstable-options" +cargo +nightly doc --all-features --open diff --git a/va108xx-hal/src/gpio/asynch.rs b/va108xx-hal/src/gpio/asynch.rs new file mode 100644 index 0000000..ab4f579 --- /dev/null +++ b/va108xx-hal/src/gpio/asynch.rs @@ -0,0 +1,449 @@ +//! # Async GPIO functionality for the VA108xx family. +//! +//! This module provides the [InputPinAsync] and [InputDynPinAsync] which both implement +//! the [embedded_hal_async::digital::Wait] trait. These types allow for asynchronous waiting +//! on GPIO pins. Please note that this module does not specify/declare the interrupt handlers +//! which must be provided for async support to work. However, it provides one generic +//! [handler][handle_interrupt_for_async_gpio] which should be called in ALL user interrupt handlers +//! for which handle GPIO interrupts. +//! +//! # Example +//! +//! - [Async GPIO example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/async-gpio/examples/embassy/src/bin/async-gpio.rs) +use core::future::Future; + +use embassy_sync::waitqueue::AtomicWaker; +use embedded_hal::digital::InputPin; +use embedded_hal_async::digital::Wait; +use portable_atomic::AtomicBool; +use va108xx::{self as pac, Irqsel, Sysconfig}; + +use crate::IrqCfg; + +use super::{ + pin, DynGroup, DynPin, DynPinId, InputConfig, InterruptEdge, InvalidPinTypeError, Pin, PinId, + NUM_GPIO_PINS, NUM_PINS_PORT_A, +}; + +static WAKERS: [AtomicWaker; NUM_GPIO_PINS] = [const { AtomicWaker::new() }; NUM_GPIO_PINS]; +static EDGE_DETECTION: [AtomicBool; NUM_GPIO_PINS] = + [const { AtomicBool::new(false) }; NUM_GPIO_PINS]; + +#[inline] +fn pin_id_to_offset(dyn_pin_id: DynPinId) -> usize { + match dyn_pin_id.group { + DynGroup::A => dyn_pin_id.num as usize, + DynGroup::B => NUM_PINS_PORT_A + dyn_pin_id.num as usize, + } +} + +/// Generic interrupt handler for GPIO interrupts to support the async functionalities. +/// +/// This handler will wake the correspoding wakers for the pins which triggered an interrupt +/// as well as updating the static edge detection structures. This allows the pin future to +/// complete async operations. The user should call this function in ALL interrupt handlers +/// which handle any GPIO interrupts. +#[inline] +pub fn handle_interrupt_for_async_gpio() { + let periphs = unsafe { pac::Peripherals::steal() }; + + handle_interrupt_for_gpio_and_port( + periphs.porta.irq_enb().read().bits(), + periphs.porta.edge_status().read().bits(), + 0, + ); + handle_interrupt_for_gpio_and_port( + periphs.portb.irq_enb().read().bits(), + periphs.portb.edge_status().read().bits(), + NUM_PINS_PORT_A, + ); +} + +// Uses the enabled interrupt register and the persistent edge status to capture all GPIO events. +#[inline] +fn handle_interrupt_for_gpio_and_port(mut irq_enb: u32, edge_status: u32, pin_base_offset: usize) { + while irq_enb != 0 { + let bit_pos = irq_enb.trailing_zeros() as usize; + let bit_mask = 1 << bit_pos; + + WAKERS[pin_base_offset + bit_pos].wake(); + + if edge_status & bit_mask != 0 { + EDGE_DETECTION[pin_base_offset + bit_pos] + .store(true, core::sync::atomic::Ordering::Relaxed); + } + + // Clear the processed bit + irq_enb &= !bit_mask; + } +} + +/// Input pin future which implements the [Future] trait. +/// +/// Generally, you want to use the [InputPinAsync] or [InputDynPinAsync] types instead of this +/// which also implements the [embedded_hal_async::digital::Wait] trait. However, access to this +/// struture is granted to allow writing custom async structures. +pub struct InputPinFuture { + pin_id: DynPinId, +} + +impl InputPinFuture { + /// # Safety + /// + /// This calls [Self::new] but uses [pac::Peripherals::steal] to get the system configuration + /// and IRQ selection peripherals. Users must ensure that the registers and configuration + /// related to this input pin are not being used elsewhere concurrently. + pub unsafe fn new_unchecked_with_dyn_pin( + pin: &mut DynPin, + irq: pac::Interrupt, + edge: InterruptEdge, + ) -> Result { + let mut periphs = pac::Peripherals::steal(); + Self::new_with_dyn_pin(pin, irq, edge, &mut periphs.sysconfig, &mut periphs.irqsel) + } + + pub fn new_with_dyn_pin( + pin: &mut DynPin, + irq: pac::Interrupt, + edge: InterruptEdge, + sys_cfg: &mut Sysconfig, + irq_sel: &mut Irqsel, + ) -> Result { + if !pin.is_input_pin() { + return Err(InvalidPinTypeError); + } + + EDGE_DETECTION[pin_id_to_offset(pin.id())] + .store(false, core::sync::atomic::Ordering::Relaxed); + pin.interrupt_edge( + edge, + IrqCfg::new(irq, true, true), + Some(sys_cfg), + Some(irq_sel), + ) + .unwrap(); + Ok(Self { pin_id: pin.id() }) + } + + /// # Safety + /// + /// This calls [Self::new] but uses [pac::Peripherals::steal] to get the system configuration + /// and IRQ selection peripherals. Users must ensure that the registers and configuration + /// related to this input pin are not being used elsewhere concurrently. + pub unsafe fn new_unchecked_with_pin( + pin: &mut Pin>, + irq: pac::Interrupt, + edge: InterruptEdge, + ) -> Self { + let mut periphs = pac::Peripherals::steal(); + Self::new_with_pin(pin, irq, edge, &mut periphs.sysconfig, &mut periphs.irqsel) + } + + pub fn new_with_pin( + pin: &mut Pin>, + irq: pac::Interrupt, + edge: InterruptEdge, + sys_cfg: &mut Sysconfig, + irq_sel: &mut Irqsel, + ) -> Self { + EDGE_DETECTION[pin_id_to_offset(pin.id())] + .store(false, core::sync::atomic::Ordering::Relaxed); + pin.interrupt_edge( + edge, + IrqCfg::new(irq, true, true), + Some(sys_cfg), + Some(irq_sel), + ); + Self { pin_id: pin.id() } + } +} + +impl Drop for InputPinFuture { + fn drop(&mut self) { + let periphs = unsafe { pac::Peripherals::steal() }; + if self.pin_id.group == DynGroup::A { + periphs + .porta + .irq_enb() + .modify(|r, w| unsafe { w.bits(r.bits() & !(1 << self.pin_id.num)) }); + } else { + periphs + .porta + .irq_enb() + .modify(|r, w| unsafe { w.bits(r.bits() & !(1 << self.pin_id.num)) }); + } + } +} + +impl Future for InputPinFuture { + type Output = (); + fn poll( + self: core::pin::Pin<&mut Self>, + cx: &mut core::task::Context<'_>, + ) -> core::task::Poll { + let idx = pin_id_to_offset(self.pin_id); + WAKERS[idx].register(cx.waker()); + if EDGE_DETECTION[idx].swap(false, core::sync::atomic::Ordering::Relaxed) { + return core::task::Poll::Ready(()); + } + core::task::Poll::Pending + } +} + +pub struct InputDynPinAsync { + pin: DynPin, + irq: pac::Interrupt, +} + +impl InputDynPinAsync { + /// Create a new asynchronous input pin from a [DynPin]. The interrupt ID to be used must be + /// passed as well and is used to route and enable the interrupt. + /// + /// Please note that the interrupt handler itself must be provided by the user and the + /// generic [handle_interrupt_for_async_gpio] function must be called inside that function for + /// the asynchronous functionality to work. + pub fn new(pin: DynPin, irq: pac::Interrupt) -> Result { + if !pin.is_input_pin() { + return Err(InvalidPinTypeError); + } + Ok(Self { pin, irq }) + } + + /// Asynchronously wait until the pin is high. + /// + /// This returns immediately if the pin is already high. + pub async fn wait_for_high(&mut self) { + let fut = unsafe { + // Unwrap okay, checked pin in constructor. + InputPinFuture::new_unchecked_with_dyn_pin( + &mut self.pin, + self.irq, + InterruptEdge::LowToHigh, + ) + .unwrap() + }; + if self.pin.is_high().unwrap() { + return; + } + fut.await; + } + + /// Asynchronously wait until the pin is low. + /// + /// This returns immediately if the pin is already high. + pub async fn wait_for_low(&mut self) { + let fut = unsafe { + // Unwrap okay, checked pin in constructor. + InputPinFuture::new_unchecked_with_dyn_pin( + &mut self.pin, + self.irq, + InterruptEdge::HighToLow, + ) + .unwrap() + }; + if self.pin.is_low().unwrap() { + return; + } + fut.await; + } + + /// Asynchronously wait until the pin sees a falling edge. + pub async fn wait_for_falling_edge(&mut self) { + unsafe { + // Unwrap okay, checked pin in constructor. + InputPinFuture::new_unchecked_with_dyn_pin( + &mut self.pin, + self.irq, + InterruptEdge::HighToLow, + ) + .unwrap() + } + .await; + } + + /// Asynchronously wait until the pin sees a rising edge. + pub async fn wait_for_rising_edge(&mut self) { + unsafe { + // Unwrap okay, checked pin in constructor. + InputPinFuture::new_unchecked_with_dyn_pin( + &mut self.pin, + self.irq, + InterruptEdge::LowToHigh, + ) + .unwrap() + } + .await; + } + + /// Asynchronously wait until the pin sees any edge (either rising or falling). + pub async fn wait_for_any_edge(&mut self) { + unsafe { + // Unwrap okay, checked pin in constructor. + InputPinFuture::new_unchecked_with_dyn_pin( + &mut self.pin, + self.irq, + InterruptEdge::BothEdges, + ) + .unwrap() + } + .await; + } + + pub fn release(self) -> DynPin { + self.pin + } +} + +impl embedded_hal::digital::ErrorType for InputDynPinAsync { + type Error = core::convert::Infallible; +} + +impl Wait for InputDynPinAsync { + async fn wait_for_high(&mut self) -> Result<(), Self::Error> { + self.wait_for_high().await; + Ok(()) + } + + async fn wait_for_low(&mut self) -> Result<(), Self::Error> { + self.wait_for_low().await; + Ok(()) + } + + async fn wait_for_rising_edge(&mut self) -> Result<(), Self::Error> { + self.wait_for_rising_edge().await; + Ok(()) + } + + async fn wait_for_falling_edge(&mut self) -> Result<(), Self::Error> { + self.wait_for_falling_edge().await; + Ok(()) + } + + async fn wait_for_any_edge(&mut self) -> Result<(), Self::Error> { + self.wait_for_any_edge().await; + Ok(()) + } +} + +pub struct InputPinAsync { + pin: Pin>, + irq: pac::Interrupt, +} + +impl InputPinAsync { + /// Create a new asynchronous input pin from a typed [Pin]. The interrupt ID to be used must be + /// passed as well and is used to route and enable the interrupt. + /// + /// Please note that the interrupt handler itself must be provided by the user and the + /// generic [handle_interrupt_for_async_gpio] function must be called inside that function for + /// the asynchronous functionality to work. + pub fn new(pin: Pin>, irq: pac::Interrupt) -> Self { + Self { pin, irq } + } + + /// Asynchronously wait until the pin is high. + /// + /// This returns immediately if the pin is already high. + pub async fn wait_for_high(&mut self) { + let fut = unsafe { + InputPinFuture::new_unchecked_with_pin( + &mut self.pin, + self.irq, + InterruptEdge::LowToHigh, + ) + }; + if self.pin.is_high().unwrap() { + return; + } + fut.await; + } + + /// Asynchronously wait until the pin is low. + /// + /// This returns immediately if the pin is already high. + pub async fn wait_for_low(&mut self) { + let fut = unsafe { + InputPinFuture::new_unchecked_with_pin( + &mut self.pin, + self.irq, + InterruptEdge::HighToLow, + ) + }; + if self.pin.is_low().unwrap() { + return; + } + fut.await; + } + + /// Asynchronously wait until the pin sees falling edge. + pub async fn wait_for_falling_edge(&mut self) { + unsafe { + // Unwrap okay, checked pin in constructor. + InputPinFuture::new_unchecked_with_pin( + &mut self.pin, + self.irq, + InterruptEdge::HighToLow, + ) + } + .await; + } + + /// Asynchronously wait until the pin sees rising edge. + pub async fn wait_for_rising_edge(&mut self) { + unsafe { + // Unwrap okay, checked pin in constructor. + InputPinFuture::new_unchecked_with_pin( + &mut self.pin, + self.irq, + InterruptEdge::LowToHigh, + ) + } + .await; + } + + /// Asynchronously wait until the pin sees any edge (either rising or falling). + pub async fn wait_for_any_edge(&mut self) { + unsafe { + InputPinFuture::new_unchecked_with_pin( + &mut self.pin, + self.irq, + InterruptEdge::BothEdges, + ) + } + .await; + } + + pub fn release(self) -> Pin> { + self.pin + } +} +impl embedded_hal::digital::ErrorType for InputPinAsync { + type Error = core::convert::Infallible; +} + +impl Wait for InputPinAsync { + async fn wait_for_high(&mut self) -> Result<(), Self::Error> { + self.wait_for_high().await; + Ok(()) + } + + async fn wait_for_low(&mut self) -> Result<(), Self::Error> { + self.wait_for_low().await; + Ok(()) + } + + async fn wait_for_rising_edge(&mut self) -> Result<(), Self::Error> { + self.wait_for_rising_edge().await; + Ok(()) + } + + async fn wait_for_falling_edge(&mut self) -> Result<(), Self::Error> { + self.wait_for_falling_edge().await; + Ok(()) + } + + async fn wait_for_any_edge(&mut self) -> Result<(), Self::Error> { + self.wait_for_any_edge().await; + Ok(()) + } +} diff --git a/va108xx-hal/src/gpio/dynpin.rs b/va108xx-hal/src/gpio/dynpin.rs index a76a3f6..aff2872 100644 --- a/va108xx-hal/src/gpio/dynpin.rs +++ b/va108xx-hal/src/gpio/dynpin.rs @@ -60,7 +60,7 @@ use super::{ pin::{FilterType, InterruptEdge, InterruptLevel, Pin, PinId, PinMode, PinState}, reg::RegisterInterface, }; -use crate::{clock::FilterClkSel, pac, FunSel, IrqCfg}; +use crate::{clock::FilterClkSel, enable_interrupt, pac, FunSel, IrqCfg}; //================================================================================================== // DynPinMode configurations @@ -172,16 +172,14 @@ pub struct DynPinId { /// /// This `struct` takes ownership of a [`DynPinId`] and provides an API to /// access the corresponding regsiters. -pub(crate) struct DynRegisters { - id: DynPinId, -} +pub(crate) struct DynRegisters(DynPinId); // [`DynRegisters`] takes ownership of the [`DynPinId`], and [`DynPin`] // guarantees that each pin is a singleton, so this implementation is safe. unsafe impl RegisterInterface for DynRegisters { #[inline] fn id(&self) -> DynPinId { - self.id + self.0 } } @@ -194,7 +192,7 @@ impl DynRegisters { /// the same [`DynPinId`] #[inline] unsafe fn new(id: DynPinId) -> Self { - DynRegisters { id } + DynRegisters(id) } } @@ -230,7 +228,7 @@ impl DynPin { /// Return a copy of the pin ID #[inline] pub fn id(&self) -> DynPinId { - self.regs.id + self.regs.0 } /// Return a copy of the pin mode @@ -249,6 +247,11 @@ impl DynPin { } } + #[inline] + pub fn is_input_pin(&self) -> bool { + matches!(self.mode, DynPinMode::Input(_)) + } + #[inline] pub fn into_funsel_1(&mut self) { self.into_mode(DYN_ALT_FUNC_1); @@ -341,6 +344,11 @@ impl DynPin { self.regs.write_pin_masked(false) } + #[inline] + pub fn edge_has_occurred(&mut self) -> bool { + self.regs.edge_has_occurred() + } + pub(crate) fn irq_enb( &mut self, irq_cfg: crate::IrqCfg, @@ -368,6 +376,9 @@ impl DynPin { } } } + if irq_cfg.enable { + unsafe { enable_interrupt(irq_cfg.irq) }; + } } /// See p.53 of the programmers guide for more information. @@ -511,7 +522,7 @@ impl DynPin { /// or refuse to perform it. #[inline] pub fn upgrade(self) -> Result, InvalidPinTypeError> { - if self.regs.id == I::DYN && self.mode == M::DYN { + if self.regs.0 == I::DYN && self.mode == M::DYN { // The `DynPin` is consumed, so it is safe to replace it with the // corresponding `Pin` return Ok(unsafe { Pin::new() }); diff --git a/va108xx-hal/src/gpio/mod.rs b/va108xx-hal/src/gpio/mod.rs index 4bdbe41..a3b6f68 100644 --- a/va108xx-hal/src/gpio/mod.rs +++ b/va108xx-hal/src/gpio/mod.rs @@ -26,10 +26,17 @@ #[cfg_attr(feature = "defmt", derive(defmt::Format))] pub struct IsMaskedError; +pub const NUM_PINS_PORT_A: usize = 32; +pub const NUM_PINS_PORT_B: usize = 24; +pub const NUM_GPIO_PINS: usize = NUM_PINS_PORT_A + NUM_PINS_PORT_B; + pub mod dynpin; pub use dynpin::*; pub mod pin; pub use pin::*; +pub mod asynch; +pub use asynch::*; + mod reg; diff --git a/va108xx-hal/src/gpio/pin.rs b/va108xx-hal/src/gpio/pin.rs index c864544..e482adf 100644 --- a/va108xx-hal/src/gpio/pin.rs +++ b/va108xx-hal/src/gpio/pin.rs @@ -342,6 +342,10 @@ impl Pin { } } + pub fn id(&self) -> DynPinId { + self.inner.id() + } + /// Convert the pin to the requested [`PinMode`] #[inline] pub fn into_mode(mut self) -> Pin { diff --git a/va108xx-hal/src/gpio/reg.rs b/va108xx-hal/src/gpio/reg.rs index f194536..d49e33e 100644 --- a/va108xx-hal/src/gpio/reg.rs +++ b/va108xx-hal/src/gpio/reg.rs @@ -327,6 +327,13 @@ pub(super) unsafe trait RegisterInterface { } } + /// Persistent bit which specifies whether an edge was detected. Reading will clear the bit. + #[inline(always)] + fn edge_has_occurred(&mut self) -> bool { + let portreg = self.port_reg(); + ((portreg.edge_status().read().bits() >> self.id().num) & 0x01) == 1 + } + /// Only useful for output pins /// See p.52 of the programmers guide for more information. /// When configured for pulse mode, a given pin will set the non-default state for exactly diff --git a/va108xx-hal/src/pwm.rs b/va108xx-hal/src/pwm.rs index 2c69165..7afdaf7 100644 --- a/va108xx-hal/src/pwm.rs +++ b/va108xx-hal/src/pwm.rs @@ -213,22 +213,6 @@ impl ReducedPwmPin { } } } -/* -impl From> for ReducedPwmPin { - fn from(pwm_pin: PwmPin) -> Self { - ReducedPwmPin { - dyn_reg: TimDynRegister { - - - } - // ::from(pwm_pin.reg), - common: pwm_pin.pwm_base, - pin_id: Pin::DYN, - mode: PhantomData, - } - } -} -*/ impl ReducedPwmPin { #[inline] diff --git a/va108xx-hal/src/timer.rs b/va108xx-hal/src/timer.rs index 58e3fcf..117ffa6 100644 --- a/va108xx-hal/src/timer.rs +++ b/va108xx-hal/src/timer.rs @@ -286,7 +286,7 @@ pub type TimRegBlock = tim0::RegisterBlock; /// /// # Safety /// -/// Users should only implement the [`tim_id`] function. No default function +/// Users should only implement the [Self::tim_id] function. No default function /// implementations should be overridden. The implementing type must also have /// "control" over the corresponding pin ID, i.e. it must guarantee that a each /// pin ID is a singleton.