Asynchronous GPIO support

This commit is contained in:
Robin Müller 2025-02-09 11:09:25 +01:00
parent 454635a473
commit c6e840a991
17 changed files with 805 additions and 43 deletions

View File

@ -44,8 +44,8 @@ fn main() -> ! {
rprintln!("-- VA108xx Test Application --");
let mut dp = pac::Peripherals::take().unwrap();
let cp = cortex_m::Peripherals::take().unwrap();
let pinsa = PinsA::new(&mut dp.sysconfig, None, dp.porta);
let pinsb = PinsB::new(&mut dp.sysconfig, Some(dp.ioconfig), dp.portb);
let pinsa = PinsA::new(&mut dp.sysconfig, dp.porta);
let pinsb = PinsB::new(&mut dp.sysconfig, dp.portb);
let mut led1 = pinsa.pa10.into_readable_push_pull_output();
let test_case = TestCase::DelayMs;

View File

@ -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"

View File

@ -0,0 +1,258 @@
//! This example demonstrates the usage of async GPIO operations on VA108xx.
//!
//! You need to tie the PA0 to the PA1 pin for this example to work. You can optionally tie the PB22 to PB23 pins well
//! and then set the `CHECK_PB22_TO_PB23` to true to also test async operations on Port B.
#![no_std]
#![no_main]
use embassy_executor::Spawner;
use embassy_sync::channel::{Receiver, Sender};
use embassy_sync::{blocking_mutex::raw::ThreadModeRawMutex, channel::Channel};
use embassy_time::{Duration, Instant, Timer};
use embedded_hal::digital::{InputPin, OutputPin, StatefulOutputPin};
use embedded_hal_async::digital::Wait;
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, InputDynPinAsync, InputPinAsync, PinsB};
use va108xx_hal::{
gpio::{DynPin, PinsA},
pac::{self, interrupt},
prelude::*,
};
const SYSCLK_FREQ: Hertz = Hertz::from_raw(50_000_000);
const CHECK_PA0_TO_PA1: bool = true;
const CHECK_PB22_TO_PB23: bool = false;
// Can also be set to OC10 and works as well.
const PB22_TO_PB23_IRQ: pac::Interrupt = pac::Interrupt::OC11;
#[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_PA0_PA1: Channel<ThreadModeRawMutex, GpioCmd, 3> = Channel::new();
static CHANNEL_PB22_TO_PB23: Channel<ThreadModeRawMutex, GpioCmd, 3> = 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, dp.porta);
let portb = PinsB::new(&mut dp.sysconfig, dp.portb);
let mut led0 = porta.pa10.into_readable_push_pull_output();
let out_pa0 = porta.pa0.into_readable_push_pull_output();
let in_pa1 = porta.pa1.into_floating_input();
let out_pb22 = portb.pb22.into_readable_push_pull_output();
let in_pb23 = portb.pb23.into_floating_input();
let in_pa1_async = InputPinAsync::new(in_pa1, pac::Interrupt::OC10);
let out_pa0_dyn = out_pa0.downgrade();
let in_pb23_async = InputDynPinAsync::new(in_pb23.downgrade(), PB22_TO_PB23_IRQ).unwrap();
let out_pb22_dyn = out_pb22.downgrade();
spawner
.spawn(output_task(
"PA0 to PA1",
out_pa0_dyn,
CHANNEL_PA0_PA1.receiver(),
))
.unwrap();
spawner
.spawn(output_task(
"PB22 to PB23",
out_pb22_dyn,
CHANNEL_PB22_TO_PB23.receiver(),
))
.unwrap();
if CHECK_PA0_TO_PA1 {
check_pin_to_pin_async_ops("PA0 to PA1", CHANNEL_PA0_PA1.sender(), in_pa1_async).await;
rprintln!("Example PA0 to PA1 done");
}
if CHECK_PB22_TO_PB23 {
check_pin_to_pin_async_ops("PB22 to PB23", CHANNEL_PB22_TO_PB23.sender(), in_pb23_async)
.await;
rprintln!("Example PB22 to PB23 done");
}
rprintln!("Example done, toggling LED0");
loop {
led0.toggle().unwrap();
Timer::after(Duration::from_millis(500)).await;
}
}
async fn check_pin_to_pin_async_ops(
ctx: &'static str,
sender: Sender<'static, ThreadModeRawMutex, GpioCmd, 3>,
mut async_input: impl Wait,
) {
rprintln!(
"{}: sending SetHigh command ({} ms)",
ctx,
Instant::now().as_millis()
);
sender.send(GpioCmd::new(GpioCmdType::SetHigh, 20)).await;
async_input.wait_for_high().await.unwrap();
rprintln!(
"{}: Input pin is high now ({} ms)",
ctx,
Instant::now().as_millis()
);
rprintln!(
"{}: sending SetLow command ({} ms)",
ctx,
Instant::now().as_millis()
);
sender.send(GpioCmd::new(GpioCmdType::SetLow, 20)).await;
async_input.wait_for_low().await.unwrap();
rprintln!(
"{}: Input pin is low now ({} ms)",
ctx,
Instant::now().as_millis()
);
rprintln!(
"{}: sending RisingEdge command ({} ms)",
ctx,
Instant::now().as_millis()
);
sender.send(GpioCmd::new(GpioCmdType::RisingEdge, 20)).await;
async_input.wait_for_rising_edge().await.unwrap();
rprintln!(
"{}: input pin had rising edge ({} ms)",
ctx,
Instant::now().as_millis()
);
rprintln!(
"{}: sending Falling command ({} ms)",
ctx,
Instant::now().as_millis()
);
sender
.send(GpioCmd::new(GpioCmdType::FallingEdge, 20))
.await;
async_input.wait_for_falling_edge().await.unwrap();
rprintln!(
"{}: input pin had a falling edge ({} ms)",
ctx,
Instant::now().as_millis()
);
rprintln!(
"{}: sending Falling command ({} ms)",
ctx,
Instant::now().as_millis()
);
sender
.send(GpioCmd::new(GpioCmdType::FallingEdge, 20))
.await;
async_input.wait_for_any_edge().await.unwrap();
rprintln!(
"{}: input pin had a falling (any) edge ({} ms)",
ctx,
Instant::now().as_millis()
);
rprintln!(
"{}: sending Falling command ({} ms)",
ctx,
Instant::now().as_millis()
);
sender.send(GpioCmd::new(GpioCmdType::RisingEdge, 20)).await;
async_input.wait_for_any_edge().await.unwrap();
rprintln!(
"{}: input pin had a rising (any) edge ({} ms)",
ctx,
Instant::now().as_millis()
);
}
#[embassy_executor::task(pool_size = 2)]
async fn output_task(
ctx: &'static str,
mut out: DynPin,
receiver: Receiver<'static, ThreadModeRawMutex, GpioCmd, 3>,
) {
loop {
let next_cmd = receiver.receive().await;
Timer::after(Duration::from_millis(next_cmd.after_delay.into())).await;
match next_cmd.cmd_type {
GpioCmdType::SetHigh => {
rprintln!("{}: Set output high", ctx);
out.set_high().unwrap();
}
GpioCmdType::SetLow => {
rprintln!("{}: Set output low", ctx);
out.set_low().unwrap();
}
GpioCmdType::RisingEdge => {
rprintln!("{}: Rising edge", ctx);
if !out.is_low().unwrap() {
out.set_low().unwrap();
}
out.set_high().unwrap();
}
GpioCmdType::FallingEdge => {
rprintln!("{}: Falling edge", ctx);
if !out.is_high().unwrap() {
out.set_high().unwrap();
}
out.set_low().unwrap();
}
}
}
}
// PB22 to PB23 can be handled by both OC10 and OC11 depending on configuration.
#[interrupt]
#[allow(non_snake_case)]
fn OC10() {
handle_interrupt_for_async_gpio();
}
#[interrupt]
#[allow(non_snake_case)]
fn OC11() {
handle_interrupt_for_async_gpio();
}

View File

@ -52,7 +52,7 @@ async fn main(_spawner: Spawner) {
}
}
let porta = PinsA::new(&mut dp.sysconfig, Some(dp.ioconfig), dp.porta);
let porta = PinsA::new(&mut dp.sysconfig, dp.porta);
let mut led0 = porta.pa10.into_readable_push_pull_output();
let mut led1 = porta.pa7.into_readable_push_pull_output();
let mut led2 = porta.pa6.into_readable_push_pull_output();

View File

@ -110,7 +110,7 @@ mod app {
let mut dp = cx.device;
let nvm = M95M01::new(&mut dp.sysconfig, SYSCLK_FREQ, dp.spic);
let gpioa = PinsA::new(&mut dp.sysconfig, Some(dp.ioconfig), dp.porta);
let gpioa = PinsA::new(&mut dp.sysconfig, dp.porta);
let tx = gpioa.pa9.into_funsel_2();
let rx = gpioa.pa8.into_funsel_2();

View File

@ -23,6 +23,7 @@ and this project adheres to [Semantic Versioning](http://semver.org/).
- `InvalidPinTypeError` now wraps the pin mode.
- I2C `TimingCfg` constructor now returns explicit error instead of generic Error.
Removed the timing configuration error type from the generic I2C error enumeration.
- `PinsA` and `PinsB` constructor do not expect an optional `pac::Ioconfig` argument anymore.
## Added

View File

@ -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"
@ -26,6 +27,8 @@ thiserror = { version = "2", default-features = false }
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 }

3
va108xx-hal/docs.sh Executable file
View File

@ -0,0 +1,3 @@
#!/bin/sh
export RUSTDOCFLAGS="--cfg docsrs --generate-link-to-definition -Z unstable-options"
cargo +nightly doc --all-features --open

View File

@ -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<Self, InvalidPinTypeError> {
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<Self, InvalidPinTypeError> {
if !pin.is_input_pin() {
return Err(InvalidPinTypeError(pin.mode()));
}
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<I: PinId, C: InputConfig>(
pin: &mut Pin<I, pin::Input<C>>,
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<I: PinId, C: InputConfig>(
pin: &mut Pin<I, pin::Input<C>>,
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<Self::Output> {
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<Self, InvalidPinTypeError> {
if !pin.is_input_pin() {
return Err(InvalidPinTypeError(pin.mode()));
}
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<I: PinId, C: InputConfig> {
pin: Pin<I, pin::Input<C>>,
irq: pac::Interrupt,
}
impl<I: PinId, C: InputConfig> InputPinAsync<I, C> {
/// 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<I, pin::Input<C>>, 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<I, pin::Input<C>> {
self.pin
}
}
impl<I: PinId, C: InputConfig> embedded_hal::digital::ErrorType for InputPinAsync<I, C> {
type Error = core::convert::Infallible;
}
impl<I: PinId, C: InputConfig> Wait for InputPinAsync<I, C> {
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(())
}
}

View File

@ -59,8 +59,9 @@
use super::{
pin::{FilterType, InterruptEdge, InterruptLevel, Pin, PinId, PinMode, PinState},
reg::RegisterInterface,
InputDynPinAsync,
};
use crate::{clock::FilterClkSel, pac, FunSel, IrqCfg};
use crate::{clock::FilterClkSel, enable_interrupt, pac, FunSel, IrqCfg};
//==================================================================================================
// DynPinMode configurations
@ -104,7 +105,7 @@ pub type DynAlternate = FunSel;
#[derive(Debug, PartialEq, Eq, thiserror::Error)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
#[error("Invalid pin type for operation: {0:?}")]
pub struct InvalidPinTypeError(DynPinMode);
pub struct InvalidPinTypeError(pub DynPinMode);
impl embedded_hal::digital::Error for InvalidPinTypeError {
fn kind(&self) -> embedded_hal::digital::ErrorKind {
@ -173,16 +174,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
}
}
@ -195,7 +194,7 @@ impl DynRegisters {
/// the same [`DynPinId`]
#[inline]
unsafe fn new(id: DynPinId) -> Self {
DynRegisters { id }
DynRegisters(id)
}
}
@ -231,7 +230,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
@ -250,6 +249,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);
@ -342,6 +346,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,
@ -369,6 +378,9 @@ impl DynPin {
}
}
}
if irq_cfg.enable {
unsafe { enable_interrupt(irq_cfg.irq) };
}
}
/// See p.53 of the programmers guide for more information.
@ -512,13 +524,22 @@ impl DynPin {
/// or refuse to perform it.
#[inline]
pub fn upgrade<I: PinId, M: PinMode>(self) -> Result<Pin<I, M>, 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() });
}
Err(InvalidPinTypeError(self.mode))
}
/// Convert the pin into an async pin. The pin can be converted back by calling
/// [InputDynPinAsync::release]
pub fn into_async_input(
self,
irq: crate::pac::Interrupt,
) -> Result<InputDynPinAsync, InvalidPinTypeError> {
InputDynPinAsync::new(self, irq)
}
}
//==================================================================================================

View File

@ -27,10 +27,17 @@
#[error("The pin is masked")]
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;

View File

@ -72,7 +72,7 @@
//! and [`StatefulOutputPin`].
use super::dynpin::{DynAlternate, DynGroup, DynInput, DynOutput, DynPinId, DynPinMode};
use super::reg::RegisterInterface;
use super::DynPin;
use super::{DynPin, InputPinAsync};
use crate::{
pac::{Irqsel, Porta, Portb, Sysconfig},
typelevel::Sealed,
@ -342,6 +342,10 @@ impl<I: PinId, M: PinMode> Pin<I, M> {
}
}
pub fn id(&self) -> DynPinId {
self.inner.id()
}
/// Convert the pin to the requested [`PinMode`]
#[inline]
pub fn into_mode<N: PinMode>(mut self) -> Pin<I, N> {
@ -571,6 +575,12 @@ impl<P: AnyPin> AsMut<P> for SpecificPin<P> {
//==================================================================================================
impl<I: PinId, C: InputConfig> Pin<I, Input<C>> {
/// Convert the pin into an async pin. The pin can be converted back by calling
/// [InputPinAsync::release]
pub fn into_async_input(self, irq: crate::pac::Interrupt) -> InputPinAsync<I, C> {
InputPinAsync::new(self, irq)
}
pub fn interrupt_edge(
&mut self,
edge_type: InterruptEdge,
@ -732,7 +742,6 @@ macro_rules! pins {
paste!(
/// Collection of all the individual [`Pin`]s for a given port (PORTA or PORTB)
pub struct $PinsName {
iocfg: Option<va108xx::Ioconfig>,
port: $Port,
$(
#[doc = "Pin " $Id]
@ -747,7 +756,6 @@ macro_rules! pins {
#[inline]
pub fn new(
syscfg: &mut va108xx::Sysconfig,
iocfg: Option<va108xx::Ioconfig>,
port: $Port
) -> $PinsName {
syscfg.peripheral_clk_enable().modify(|_, w| {
@ -756,7 +764,7 @@ macro_rules! pins {
w.ioconfig().set_bit()
});
$PinsName {
iocfg,
//iocfg,
port,
// Safe because we only create one `Pin` per `PinId`
$(
@ -773,8 +781,8 @@ macro_rules! pins {
}
/// Consumes the Pins struct and returns the port definitions
pub fn release(self) -> (Option<va108xx::Ioconfig>, $Port) {
(self.iocfg, self.port)
pub fn release(self) -> $Port {
self.port
}
}
);

View File

@ -73,13 +73,6 @@ impl From<DynPinMode> for ModeFields {
//==================================================================================================
pub type PortReg = ioconfig::Porta;
/*
pub type IocfgPort = ioconfig::Porta;
#[repr(C)]
pub(super) struct IocfgPortGroup {
port: [IocfgPort; 32],
}
*/
/// Provide a safe register interface for pin objects
///

View File

@ -213,22 +213,6 @@ impl<Mode> ReducedPwmPin<Mode> {
}
}
}
/*
impl<Pin: TimPin, Tim: ValidTim> From<PwmPin<Pin, Tim>> for ReducedPwmPin<PwmA> {
fn from(pwm_pin: PwmPin<Pin, Tim>) -> Self {
ReducedPwmPin {
dyn_reg: TimDynRegister {
}
// ::from(pwm_pin.reg),
common: pwm_pin.pwm_base,
pin_id: Pin::DYN,
mode: PhantomData,
}
}
}
*/
impl<Mode> ReducedPwmPin<Mode> {
#[inline]

View File

@ -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.

View File

@ -499,5 +499,29 @@
]
}
},
{
"type": "cortex-debug",
"request": "launch",
"name": "Async GPIO",
"servertype": "jlink",
"cwd": "${workspaceRoot}",
"device": "Cortex-M0",
"svdFile": "./va108xx/svd/va108xx.svd.patched",
"preLaunchTask": "async-gpio",
"executable": "${workspaceFolder}/target/thumbv6m-none-eabi/debug/async-gpio",
"interface": "jtag",
"runToEntryPoint": "main",
"rttConfig": {
"enabled": true,
"address": "auto",
"decoders": [
{
"port": 0,
"timestamp": true,
"type": "console"
}
]
}
},
]
}

View File

@ -266,6 +266,16 @@
"embassy-example"
]
},
{
"label": "async-gpio",
"type": "shell",
"command": "~/.cargo/bin/cargo", // note: full path to the cargo
"args": [
"build",
"--bin",
"async-gpio"
]
},
{
"label": "bootloader",
"type": "shell",