Merge branch 'master' of https://github.com/akiles/embassy into st-usb

This commit is contained in:
xoviat 2021-03-27 21:24:21 -05:00
commit 3242990690
25 changed files with 638 additions and 349 deletions

View File

@ -52,6 +52,9 @@ jobs:
- package: embassy-stm32f4
target: thumbv7em-none-eabi
features: stm32f405
- package: embassy-stm32f4
target: thumbv7em-none-eabi
features: stm32f446
- package: embassy-stm32f4
target: thumbv7em-none-eabi
features: stm32f405,defmt

View File

@ -1,6 +1,7 @@
{
"rust-analyzer.assist.importMergeBehavior": "last",
"editor.formatOnSave": true,
"rust.target": "thumbv7em-none-eabihf",
"rust-analyzer.cargo.allFeatures": false,
"rust-analyzer.checkOnSave.allFeatures": false,
"rust-analyzer.checkOnSave.allTargets": false,

View File

@ -1,6 +1,7 @@
# Embassy
Embassy is a project to make async/await a first-class option for embedded development.
Embassy is a project to make async/await a first-class option for embedded development. For more information and instructions to
get started, click [here](https://github.com/embassy-rs/embassy/wiki).
## Traits and types

View File

@ -43,5 +43,7 @@ cortex-m-rt = "0.6.13"
cortex-m = "0.7.1"
embedded-hal = { version = "0.2.4" }
embedded-dma = { version = "0.1.2" }
bxcan = "0.5.0"
nb = "*"
stm32f4xx-hal = { version = "0.8.3", features = ["rt", "can"], git = "https://github.com/stm32-rs/stm32f4xx-hal.git", optional = true }
stm32l0xx-hal = { version = "0.7.0", features = ["rt"], git = "https://github.com/stm32-rs/stm32l0xx-hal.git", optional = true }
stm32l0xx-hal = { version = "0.7.0", features = ["rt"], optional = true }

View File

@ -95,6 +95,25 @@ macro_rules! can {
}
}
#[cfg(any(
feature = "stm32f401",
feature = "stm32f405",
feature = "stm32f407",
feature = "stm32f410",
feature = "stm32f411",
feature = "stm32f412",
feature = "stm32f413",
feature = "stm32f415",
feature = "stm32f417",
feature = "stm32f423",
feature = "stm32f427",
feature = "stm32f429",
feature = "stm32f437",
feature = "stm32f439",
feature = "stm32f446",
feature = "stm32f469",
feature = "stm32f479",
))]
can! {
CAN1 => (CAN1_TX, CAN1_RX0),
CAN2 => (CAN2_TX, CAN2_RX0),

View File

@ -3,35 +3,57 @@ use core::mem;
use core::pin::Pin;
use cortex_m;
use embassy::traits::gpio::{WaitForFallingEdge, WaitForRisingEdge};
use crate::hal::gpio;
#[cfg(any(
feature = "stm32f401",
feature = "stm32f405",
feature = "stm32f407",
feature = "stm32f410",
feature = "stm32f411",
feature = "stm32f412",
feature = "stm32f413",
feature = "stm32f415",
feature = "stm32f417",
feature = "stm32f423",
feature = "stm32f427",
feature = "stm32f429",
feature = "stm32f437",
feature = "stm32f439",
feature = "stm32f446",
feature = "stm32f469",
feature = "stm32f479",
))]
use crate::hal::syscfg::SysCfg;
#[cfg(any(feature = "stm32l0x1", feature = "stm32l0x2", feature = "stm32l0x3",))]
use crate::hal::syscfg::SYSCFG as SysCfg;
use embassy::traits::gpio::{
WaitForAnyEdge, WaitForFallingEdge, WaitForHigh, WaitForLow, WaitForRisingEdge,
};
use embassy::util::InterruptFuture;
use crate::hal::gpio;
use crate::hal::gpio::Edge;
use crate::hal::syscfg::SysCfg;
use crate::pac::EXTI;
use embedded_hal::digital::v2 as digital;
use crate::interrupt;
pub struct ExtiPin<T: gpio::ExtiPin + WithInterrupt> {
pub struct ExtiPin<T: Instance> {
pin: T,
interrupt: T::Interrupt,
}
impl<T: gpio::ExtiPin + WithInterrupt> ExtiPin<T> {
pub fn new(mut pin: T, interrupt: T::Interrupt) -> Self {
let mut syscfg: SysCfg = unsafe { mem::transmute(()) };
impl<T: Instance> ExtiPin<T> {
pub fn new(mut pin: T, interrupt: T::Interrupt, syscfg: &mut SysCfg) -> Self {
cortex_m::interrupt::free(|_| {
pin.make_interrupt_source(&mut syscfg);
pin.make_source(syscfg);
});
Self { pin, interrupt }
}
}
impl<T: gpio::ExtiPin + WithInterrupt + digital::OutputPin> digital::OutputPin for ExtiPin<T> {
impl<T: Instance + digital::OutputPin> digital::OutputPin for ExtiPin<T> {
type Error = T::Error;
fn set_low(&mut self) -> Result<(), Self::Error> {
@ -43,9 +65,7 @@ impl<T: gpio::ExtiPin + WithInterrupt + digital::OutputPin> digital::OutputPin f
}
}
impl<T: gpio::ExtiPin + WithInterrupt + digital::StatefulOutputPin> digital::StatefulOutputPin
for ExtiPin<T>
{
impl<T: Instance + digital::StatefulOutputPin> digital::StatefulOutputPin for ExtiPin<T> {
fn is_set_low(&self) -> Result<bool, Self::Error> {
self.pin.is_set_low()
}
@ -55,9 +75,7 @@ impl<T: gpio::ExtiPin + WithInterrupt + digital::StatefulOutputPin> digital::Sta
}
}
impl<T: gpio::ExtiPin + WithInterrupt + digital::ToggleableOutputPin> digital::ToggleableOutputPin
for ExtiPin<T>
{
impl<T: Instance + digital::ToggleableOutputPin> digital::ToggleableOutputPin for ExtiPin<T> {
type Error = T::Error;
fn toggle(&mut self) -> Result<(), Self::Error> {
@ -65,7 +83,7 @@ impl<T: gpio::ExtiPin + WithInterrupt + digital::ToggleableOutputPin> digital::T
}
}
impl<T: gpio::ExtiPin + WithInterrupt + digital::InputPin> digital::InputPin for ExtiPin<T> {
impl<T: Instance + digital::InputPin> digital::InputPin for ExtiPin<T> {
type Error = T::Error;
fn is_high(&self) -> Result<bool, Self::Error> {
@ -77,6 +95,73 @@ impl<T: gpio::ExtiPin + WithInterrupt + digital::InputPin> digital::InputPin for
}
}
impl<T: Instance + digital::InputPin + 'static> ExtiPin<T> {
fn wait_for_state<'a>(self: Pin<&'a mut Self>, state: bool) -> impl Future<Output = ()> + 'a {
let s = unsafe { self.get_unchecked_mut() };
s.pin.clear_pending_bit();
async move {
let fut = InterruptFuture::new(&mut s.interrupt);
let pin = &mut s.pin;
cortex_m::interrupt::free(|_| {
pin.trigger_edge(if state {
EdgeOption::Rising
} else {
EdgeOption::Falling
});
});
if (state && s.pin.is_high().unwrap_or(false))
|| (!state && s.pin.is_low().unwrap_or(false))
{
return;
}
fut.await;
s.pin.clear_pending_bit();
}
}
}
impl<T: Instance + 'static> ExtiPin<T> {
fn wait_for_edge<'a>(
self: Pin<&'a mut Self>,
state: EdgeOption,
) -> impl Future<Output = ()> + 'a {
let s = unsafe { self.get_unchecked_mut() };
s.pin.clear_pending_bit();
async move {
let fut = InterruptFuture::new(&mut s.interrupt);
let pin = &mut s.pin;
cortex_m::interrupt::free(|_| {
pin.trigger_edge(state);
});
fut.await;
s.pin.clear_pending_bit();
}
}
}
impl<T: Instance + digital::InputPin + 'static> WaitForHigh for ExtiPin<T> {
type Future<'a> = impl Future<Output = ()> + 'a;
fn wait_for_high<'a>(self: Pin<&'a mut Self>) -> Self::Future<'a> {
self.wait_for_state(true)
}
}
impl<T: Instance + digital::InputPin + 'static> WaitForLow for ExtiPin<T> {
type Future<'a> = impl Future<Output = ()> + 'a;
fn wait_for_low<'a>(self: Pin<&'a mut Self>) -> Self::Future<'a> {
self.wait_for_state(false)
}
}
/*
Irq Handler Description
EXTI0_IRQn EXTI0_IRQHandler Handler for pins connected to line 0
@ -88,60 +173,51 @@ impl<T: gpio::ExtiPin + WithInterrupt + digital::InputPin> digital::InputPin for
EXTI15_10_IRQn EXTI15_10_IRQHandler Handler for pins connected to line 10 to 15
*/
impl<T: gpio::ExtiPin + WithInterrupt + 'static> WaitForRisingEdge for ExtiPin<T> {
impl<T: Instance + 'static> WaitForRisingEdge for ExtiPin<T> {
type Future<'a> = impl Future<Output = ()> + 'a;
fn wait_for_rising_edge<'a>(self: Pin<&'a mut Self>) -> Self::Future<'a> {
let s = unsafe { self.get_unchecked_mut() };
s.pin.clear_interrupt_pending_bit();
async move {
let fut = InterruptFuture::new(&mut s.interrupt);
let pin = &mut s.pin;
cortex_m::interrupt::free(|_| {
let mut exti: EXTI = unsafe { mem::transmute(()) };
pin.trigger_on_edge(&mut exti, Edge::RISING);
pin.enable_interrupt(&mut exti);
});
fut.await;
s.pin.clear_interrupt_pending_bit();
}
self.wait_for_edge(EdgeOption::Rising)
}
}
impl<T: gpio::ExtiPin + WithInterrupt + 'static> WaitForFallingEdge for ExtiPin<T> {
impl<T: Instance + 'static> WaitForFallingEdge for ExtiPin<T> {
type Future<'a> = impl Future<Output = ()> + 'a;
fn wait_for_falling_edge<'a>(self: Pin<&'a mut Self>) -> Self::Future<'a> {
let s = unsafe { self.get_unchecked_mut() };
s.pin.clear_interrupt_pending_bit();
async move {
let fut = InterruptFuture::new(&mut s.interrupt);
let pin = &mut s.pin;
cortex_m::interrupt::free(|_| {
let mut exti: EXTI = unsafe { mem::transmute(()) };
pin.trigger_on_edge(&mut exti, Edge::FALLING);
pin.enable_interrupt(&mut exti);
});
fut.await;
s.pin.clear_interrupt_pending_bit();
self.wait_for_edge(EdgeOption::Falling)
}
}
impl<T: Instance + 'static> WaitForAnyEdge for ExtiPin<T> {
type Future<'a> = impl Future<Output = ()> + 'a;
fn wait_for_any_edge<'a>(self: Pin<&'a mut Self>) -> Self::Future<'a> {
self.wait_for_edge(EdgeOption::RisingFalling)
}
}
mod private {
pub trait Sealed {}
}
#[derive(Copy, Clone)]
pub enum EdgeOption {
Rising,
Falling,
RisingFalling,
}
pub trait WithInterrupt: private::Sealed {
type Interrupt: interrupt::Interrupt;
}
pub trait Instance: WithInterrupt {
fn make_source(&mut self, syscfg: &mut SysCfg);
fn clear_pending_bit(&mut self);
fn trigger_edge(&mut self, edge: EdgeOption);
}
macro_rules! exti {
($set:ident, [
$($INT:ident => $pin:ident,)+
@ -151,8 +227,88 @@ macro_rules! exti {
impl<T> WithInterrupt for gpio::$set::$pin<T> {
type Interrupt = interrupt::$INT;
}
)+
#[cfg(any(
feature = "stm32f401",
feature = "stm32f405",
feature = "stm32f407",
feature = "stm32f410",
feature = "stm32f411",
feature = "stm32f412",
feature = "stm32f413",
feature = "stm32f415",
feature = "stm32f417",
feature = "stm32f423",
feature = "stm32f427",
feature = "stm32f429",
feature = "stm32f437",
feature = "stm32f439",
feature = "stm32f446",
feature = "stm32f469",
feature = "stm32f479",
))]
impl<T> Instance for gpio::$set::$pin<gpio::Input<T>> {
fn make_source(&mut self, syscfg: &mut SysCfg) {
use crate::hal::gpio::ExtiPin;
self.make_interrupt_source(syscfg);
}
fn clear_pending_bit(&mut self) {
use crate::hal::{gpio::Edge, gpio::ExtiPin, syscfg::SysCfg};
self.clear_interrupt_pending_bit();
}
fn trigger_edge(&mut self, edge: EdgeOption) {
use crate::hal::{gpio::Edge, gpio::ExtiPin, syscfg::SysCfg};
use crate::pac::EXTI;
let mut exti: EXTI = unsafe { mem::transmute(()) };
let edge = match edge {
EdgeOption::Falling => Edge::FALLING,
EdgeOption::Rising => Edge::RISING,
EdgeOption::RisingFalling => Edge::RISING_FALLING,
};
self.trigger_on_edge(&mut exti, edge);
self.enable_interrupt(&mut exti);
}
}
#[cfg(any(feature = "stm32l0x1", feature = "stm32l0x2", feature = "stm32l0x3",))]
impl<T> Instance for gpio::$set::$pin<T> {
fn make_source(&mut self, syscfg: &mut SysCfg) {}
fn clear_pending_bit(&mut self) {
use crate::hal::{
exti::{Exti, ExtiLine, GpioLine, TriggerEdge},
syscfg::SYSCFG,
};
Exti::unpend(GpioLine::from_raw_line(self.pin_number()).unwrap());
}
fn trigger_edge(&mut self, edge: EdgeOption) {
use crate::hal::{
exti::{Exti, ExtiLine, GpioLine, TriggerEdge},
syscfg::SYSCFG,
};
use crate::pac::EXTI;
let edge = match edge {
EdgeOption::Falling => TriggerEdge::Falling,
EdgeOption::Rising => TriggerEdge::Rising,
EdgeOption::RisingFalling => TriggerEdge::Both,
};
let exti: EXTI = unsafe { mem::transmute(()) };
let mut exti = Exti::new(exti);
let port = self.port();
let mut syscfg: SYSCFG = unsafe { mem::transmute(()) };
let line = GpioLine::from_raw_line(self.pin_number()).unwrap();
exti.listen_gpio(&mut syscfg, port, line, edge);
}
}
)+
};
}
@ -533,3 +689,111 @@ exti!(gpiok, [
EXTI9_5 => PK6,
EXTI9_5 => PK7,
]);
#[cfg(any(feature = "stm32l0x1", feature = "stm32l0x2", feature = "stm32l0x3",))]
exti!(gpioa, [
EXTI0_1 => PA0,
EXTI0_1 => PA1,
EXTI2_3 => PA2,
EXTI2_3 => PA3,
EXTI4_15 => PA4,
EXTI4_15 => PA5,
EXTI4_15 => PA6,
EXTI4_15 => PA7,
EXTI4_15 => PA8,
EXTI4_15 => PA9,
EXTI4_15 => PA10,
EXTI4_15 => PA11,
EXTI4_15 => PA12,
EXTI4_15 => PA13,
EXTI4_15 => PA14,
EXTI4_15 => PA15,
]);
#[cfg(any(feature = "stm32l0x1", feature = "stm32l0x2", feature = "stm32l0x3",))]
exti!(gpiob, [
EXTI0_1 => PB0,
EXTI0_1 => PB1,
EXTI2_3 => PB2,
EXTI2_3 => PB3,
EXTI4_15 => PB4,
EXTI4_15 => PB5,
EXTI4_15 => PB6,
EXTI4_15 => PB7,
EXTI4_15 => PB8,
EXTI4_15 => PB9,
EXTI4_15 => PB10,
EXTI4_15 => PB11,
EXTI4_15 => PB12,
EXTI4_15 => PB13,
EXTI4_15 => PB14,
EXTI4_15 => PB15,
]);
#[cfg(any(feature = "stm32l0x1", feature = "stm32l0x2", feature = "stm32l0x3",))]
exti!(gpioc, [
EXTI0_1 => PC0,
EXTI0_1 => PC1,
EXTI2_3 => PC2,
EXTI2_3 => PC3,
EXTI4_15 => PC4,
EXTI4_15 => PC5,
EXTI4_15 => PC6,
EXTI4_15 => PC7,
EXTI4_15 => PC8,
EXTI4_15 => PC9,
EXTI4_15 => PC10,
EXTI4_15 => PC11,
EXTI4_15 => PC12,
EXTI4_15 => PC13,
EXTI4_15 => PC14,
EXTI4_15 => PC15,
]);
#[cfg(any(feature = "stm32l0x1", feature = "stm32l0x2", feature = "stm32l0x3",))]
exti!(gpiod, [
EXTI0_1 => PD0,
EXTI0_1 => PD1,
EXTI2_3 => PD2,
EXTI2_3 => PD3,
EXTI4_15 => PD4,
EXTI4_15 => PD5,
EXTI4_15 => PD6,
EXTI4_15 => PD7,
EXTI4_15 => PD8,
EXTI4_15 => PD9,
EXTI4_15 => PD10,
EXTI4_15 => PD11,
EXTI4_15 => PD12,
EXTI4_15 => PD13,
EXTI4_15 => PD14,
EXTI4_15 => PD15,
]);
#[cfg(any(feature = "stm32l0x1", feature = "stm32l0x2", feature = "stm32l0x3",))]
exti!(gpioe, [
EXTI0_1 => PE0,
EXTI0_1 => PE1,
EXTI2_3 => PE2,
EXTI2_3 => PE3,
EXTI4_15 => PE4,
EXTI4_15 => PE5,
EXTI4_15 => PE6,
EXTI4_15 => PE7,
EXTI4_15 => PE8,
EXTI4_15 => PE9,
EXTI4_15 => PE10,
EXTI4_15 => PE11,
EXTI4_15 => PE12,
EXTI4_15 => PE13,
EXTI4_15 => PE14,
EXTI4_15 => PE15,
]);
#[cfg(any(feature = "stm32l0x1", feature = "stm32l0x2", feature = "stm32l0x3",))]
exti!(gpioh, [
EXTI0_1 => PH0,
EXTI0_1 => PH1,
EXTI4_15 => PH9,
EXTI4_15 => PH10,
]);

View File

@ -889,7 +889,7 @@ mod irqs {
declare!(TIM8_CC);
declare!(DMA1_STREAM7);
declare!(FMC);
declare!(SDIO);
// declare!(SDIO);
declare!(TIM5);
declare!(SPI3);
declare!(UART4);

View File

@ -32,12 +32,33 @@ pub use {stm32l0xx_hal as hal, stm32l0xx_hal::pac};
pub mod fmt;
pub mod exti;
pub mod interrupt;
#[cfg(any(
feature = "stm32f401",
feature = "stm32f405",
feature = "stm32f407",
feature = "stm32f412",
feature = "stm32f413",
feature = "stm32f415",
feature = "stm32f417",
feature = "stm32f423",
feature = "stm32f427",
feature = "stm32f429",
feature = "stm32f437",
feature = "stm32f439",
feature = "stm32f446",
feature = "stm32f469",
feature = "stm32f479",
))]
pub mod can;
#[cfg(any(
feature = "stm32f401",
feature = "stm32f405",
feature = "stm32f407",
feature = "stm32f410",
feature = "stm32f411",
feature = "stm32f412",
feature = "stm32f413",
@ -52,4 +73,6 @@ pub mod interrupt;
feature = "stm32f469",
feature = "stm32f479",
))]
pub mod rtc;
unsafe impl embassy_extras::usb::USBInterrupt for interrupt::OTG_FS {}

View File

@ -24,8 +24,9 @@ async fn run(dp: stm32::Peripherals, _cp: cortex_m::Peripherals) {
let gpioa = dp.GPIOA.split();
let button = gpioa.pa0.into_pull_up_input();
let mut syscfg = dp.SYSCFG.constrain();
let pin = ExtiPin::new(button, interrupt::take!(EXTI0));
let pin = ExtiPin::new(button, interrupt::take!(EXTI0), &mut syscfg);
pin_mut!(pin);
info!("Starting loop");

View File

@ -37,6 +37,7 @@ defmt = { version = "0.2.0", optional = true }
log = { version = "0.4.11", optional = true }
cortex-m-rt = "0.6.13"
cortex-m = "0.7.1"
futures = { version = "0.3.5", default-features = false, features = ["async-await"] }
embedded-hal = { version = "0.2.4" }
embedded-dma = { version = "0.1.2" }
stm32f4xx-hal = { version = "0.8.3", features = ["rt", "can"], git = "https://github.com/stm32-rs/stm32f4xx-hal.git"}

View File

@ -307,12 +307,11 @@ compile_error!(
"Multile chip features activated. You must activate exactly one of the following features: "
);
pub use embassy_stm32::{fmt, hal, interrupt, pac};
pub use embassy_stm32::{exti, fmt, hal, interrupt, pac, rtc};
#[cfg(not(any(feature = "stm32f401", feature = "stm32f410", feature = "stm32f411",)))]
pub mod can;
pub mod exti;
pub use embassy_stm32::can;
#[cfg(not(feature = "stm32f410"))]
pub mod qei;
pub mod rtc;
pub mod serial;

View File

@ -7,8 +7,10 @@
use core::future::Future;
use core::marker::PhantomData;
use futures::{select_biased, FutureExt};
use embassy::interrupt::Interrupt;
use embassy::traits::uart::{Error, Uart};
use embassy::traits::uart::{Error, IdleUart, Uart};
use embassy::util::InterruptFuture;
use crate::hal::{
@ -19,7 +21,7 @@ use crate::hal::{
rcc::Clocks,
serial,
serial::config::{Config as SerialConfig, DmaConfig as SerialDmaConfig},
serial::{Event as SerialEvent, Pins, Serial as HalSerial},
serial::{Event as SerialEvent, Pins},
};
use crate::interrupt;
use crate::pac;
@ -29,14 +31,14 @@ pub struct Serial<
USART: PeriAddress<MemSize = u8> + WithInterrupt,
TSTREAM: Stream + WithInterrupt,
RSTREAM: Stream + WithInterrupt,
CHANNEL: dma::traits::Channel,
CHANNEL: Channel,
> {
tx_stream: Option<TSTREAM>,
rx_stream: Option<RSTREAM>,
usart: Option<USART>,
tx_int: TSTREAM::Interrupt,
rx_int: RSTREAM::Interrupt,
_usart_int: USART::Interrupt,
usart_int: USART::Interrupt,
channel: PhantomData<CHANNEL>,
}
@ -68,12 +70,10 @@ where
PINS: Pins<USART>,
{
config.dma = SerialDmaConfig::TxRx;
let mut serial = HalSerial::new(usart, pins, config, clocks).unwrap();
serial.listen(SerialEvent::Idle);
// serial.listen(SerialEvent::Txe);
let (usart, _) = serial.release();
let (usart, _) = serial::Serial::new(usart, pins, config, clocks)
.unwrap()
.release();
let (tx_stream, rx_stream) = streams;
@ -83,8 +83,8 @@ where
usart: Some(usart),
tx_int: tx_int,
rx_int: rx_int,
_usart_int: usart_int,
channel: core::marker::PhantomData,
usart_int: usart_int,
channel: PhantomData,
}
}
}
@ -127,10 +127,10 @@ where
let fut = InterruptFuture::new(&mut self.tx_int);
tx_transfer.start(|_usart| {});
fut.await;
let (tx_stream, usart, _buf, _) = tx_transfer.free();
self.tx_stream.replace(tx_stream);
self.usart.replace(usart);
@ -163,7 +163,6 @@ where
);
let fut = InterruptFuture::new(&mut self.rx_int);
rx_transfer.start(|_usart| {});
fut.await;
@ -176,6 +175,79 @@ where
}
}
impl<USART, TSTREAM, RSTREAM, CHANNEL> IdleUart for Serial<USART, TSTREAM, RSTREAM, CHANNEL>
where
USART: serial::Instance
+ PeriAddress<MemSize = u8>
+ DMASet<TSTREAM, CHANNEL, MemoryToPeripheral>
+ DMASet<RSTREAM, CHANNEL, PeripheralToMemory>
+ WithInterrupt
+ 'static,
TSTREAM: Stream + WithInterrupt + 'static,
RSTREAM: Stream + WithInterrupt + 'static,
CHANNEL: Channel + 'static,
{
type ReceiveFuture<'a> = impl Future<Output = Result<usize, Error>> + 'a;
/// Receives serial data.
///
/// The future is pending until either the buffer is completely full, or the RX line falls idle after receiving some data.
///
/// Returns the number of bytes read.
fn receive_until_idle<'a>(&'a mut self, buf: &'a mut [u8]) -> Self::ReceiveFuture<'a> {
let static_buf = unsafe { core::mem::transmute::<&'a mut [u8], &'static mut [u8]>(buf) };
let rx_stream = self.rx_stream.take().unwrap();
let usart = self.usart.take().unwrap();
async move {
unsafe {
/* __HAL_UART_ENABLE_IT(&uart->UartHandle, UART_IT_IDLE); */
(*USART::ptr()).cr1.modify(|_, w| w.idleie().set_bit());
/* __HAL_UART_CLEAR_IDLEFLAG(&uart->UartHandle); */
(*USART::ptr()).sr.read();
(*USART::ptr()).dr.read();
};
let mut rx_transfer = Transfer::init(
rx_stream,
usart,
static_buf,
None,
DmaConfig::default()
.transfer_complete_interrupt(true)
.memory_increment(true)
.double_buffer(false),
);
let total_bytes = RSTREAM::get_number_of_transfers() as usize;
let fut = InterruptFuture::new(&mut self.rx_int);
let fut_idle = InterruptFuture::new(&mut self.usart_int);
rx_transfer.start(|_usart| {});
select_biased! {
() = fut.fuse() => {},
() = fut_idle.fuse() => {},
}
let (rx_stream, usart, _, _) = rx_transfer.free();
let remaining_bytes = RSTREAM::get_number_of_transfers() as usize;
unsafe {
(*USART::ptr()).cr1.modify(|_, w| w.idleie().clear_bit());
}
self.rx_stream.replace(rx_stream);
self.usart.replace(usart);
Ok(total_bytes - remaining_bytes)
}
}
}
mod private {
pub trait Sealed {}
}
@ -278,6 +350,6 @@ usart! {
UART4 => (UART4),
UART5 => (UART5),
UART7 => (UART7),
UART8 => (UART8),
// UART7 => (UART7),
// UART8 => (UART8),
}

View File

@ -1,268 +0,0 @@
use core::future::Future;
use core::mem;
use core::pin::Pin;
use embassy::traits::gpio::{
WaitForAnyEdge, WaitForFallingEdge, WaitForHigh, WaitForLow, WaitForRisingEdge,
};
use embassy::util::InterruptFuture;
use crate::hal::{
exti::{Exti, ExtiLine, GpioLine, TriggerEdge},
gpio,
syscfg::SYSCFG,
};
use crate::interrupt;
use crate::pac::EXTI;
use embedded_hal::digital::v2::InputPin;
pub struct ExtiPin<T: PinWithInterrupt> {
pin: T,
interrupt: T::Interrupt,
}
impl<T: PinWithInterrupt + 'static> ExtiPin<T> {
pub fn new(pin: T, interrupt: T::Interrupt) -> ExtiPin<T> {
ExtiPin { pin, interrupt }
}
fn wait_for_edge<'a>(
self: Pin<&'a mut Self>,
edge: TriggerEdge,
) -> impl Future<Output = ()> + 'a {
let line = self.pin.line();
let s = unsafe { self.get_unchecked_mut() };
Exti::unpend(line);
async move {
let exti: EXTI = unsafe { mem::transmute(()) };
let mut exti = Exti::new(exti);
let fut = InterruptFuture::new(&mut s.interrupt);
let port = s.pin.port();
cortex_m::interrupt::free(|_| {
let mut syscfg: SYSCFG = unsafe { mem::transmute(()) };
exti.listen_gpio(&mut syscfg, port, line, edge);
});
fut.await;
Exti::unpend(line);
}
}
}
impl<T: InputPin + PinWithInterrupt + 'static> ExtiPin<T> {
fn wait_for_state<'a>(self: Pin<&'a mut Self>, state: bool) -> impl Future<Output = ()> + 'a {
let line = self.pin.line();
let s = unsafe { self.get_unchecked_mut() };
Exti::unpend(line);
async move {
let exti: EXTI = unsafe { mem::transmute(()) };
let mut exti = Exti::new(exti);
let fut = InterruptFuture::new(&mut s.interrupt);
let port = s.pin.port();
cortex_m::interrupt::free(|_| {
let mut syscfg: SYSCFG = unsafe { mem::transmute(()) };
let edge = if state {
TriggerEdge::Rising
} else {
TriggerEdge::Falling
};
exti.listen_gpio(&mut syscfg, port, line, edge);
});
let pin_has_state = if state {
s.pin.is_high()
} else {
s.pin.is_low()
}
.unwrap_or(false);
if pin_has_state {
return ();
}
fut.await;
Exti::unpend(line);
}
}
}
impl<T: PinWithInterrupt + 'static> WaitForRisingEdge for ExtiPin<T> {
type Future<'a> = impl Future<Output = ()> + 'a;
fn wait_for_rising_edge<'a>(self: Pin<&'a mut Self>) -> Self::Future<'a> {
self.wait_for_edge(TriggerEdge::Rising)
}
}
impl<T: PinWithInterrupt + 'static> WaitForFallingEdge for ExtiPin<T> {
type Future<'a> = impl Future<Output = ()> + 'a;
fn wait_for_falling_edge<'a>(self: Pin<&'a mut Self>) -> Self::Future<'a> {
self.wait_for_edge(TriggerEdge::Falling)
}
}
impl<T: PinWithInterrupt + 'static> WaitForAnyEdge for ExtiPin<T> {
type Future<'a> = impl Future<Output = ()> + 'a;
fn wait_for_any_edge<'a>(self: Pin<&'a mut Self>) -> Self::Future<'a> {
self.wait_for_edge(TriggerEdge::Both)
}
}
impl<T: InputPin + PinWithInterrupt + 'static> WaitForHigh for ExtiPin<T> {
type Future<'a> = impl Future<Output = ()> + 'a;
fn wait_for_high<'a>(self: Pin<&'a mut Self>) -> Self::Future<'a> {
self.wait_for_state(true)
}
}
impl<T: InputPin + PinWithInterrupt + 'static> WaitForLow for ExtiPin<T> {
type Future<'a> = impl Future<Output = ()> + 'a;
fn wait_for_low<'a>(self: Pin<&'a mut Self>) -> Self::Future<'a> {
self.wait_for_state(false)
}
}
mod private {
pub trait Sealed {}
}
pub trait PinWithInterrupt: private::Sealed {
type Interrupt: interrupt::Interrupt;
fn port(&self) -> gpio::Port;
fn line(&self) -> GpioLine;
}
macro_rules! exti {
($set:ident, [
$($INT:ident => $pin:ident,)+
]) => {
$(
impl<T> private::Sealed for gpio::$set::$pin<T> {}
impl<T> PinWithInterrupt for gpio::$set::$pin<T> {
type Interrupt = interrupt::$INT;
fn port(&self) -> gpio::Port {
self.port()
}
fn line(&self) -> GpioLine {
GpioLine::from_raw_line(self.pin_number()).unwrap()
}
}
)+
};
}
exti!(gpioa, [
EXTI0_1 => PA0,
EXTI0_1 => PA1,
EXTI2_3 => PA2,
EXTI2_3 => PA3,
EXTI4_15 => PA4,
EXTI4_15 => PA5,
EXTI4_15 => PA6,
EXTI4_15 => PA7,
EXTI4_15 => PA8,
EXTI4_15 => PA9,
EXTI4_15 => PA10,
EXTI4_15 => PA11,
EXTI4_15 => PA12,
EXTI4_15 => PA13,
EXTI4_15 => PA14,
EXTI4_15 => PA15,
]);
exti!(gpiob, [
EXTI0_1 => PB0,
EXTI0_1 => PB1,
EXTI2_3 => PB2,
EXTI2_3 => PB3,
EXTI4_15 => PB4,
EXTI4_15 => PB5,
EXTI4_15 => PB6,
EXTI4_15 => PB7,
EXTI4_15 => PB8,
EXTI4_15 => PB9,
EXTI4_15 => PB10,
EXTI4_15 => PB11,
EXTI4_15 => PB12,
EXTI4_15 => PB13,
EXTI4_15 => PB14,
EXTI4_15 => PB15,
]);
exti!(gpioc, [
EXTI0_1 => PC0,
EXTI0_1 => PC1,
EXTI2_3 => PC2,
EXTI2_3 => PC3,
EXTI4_15 => PC4,
EXTI4_15 => PC5,
EXTI4_15 => PC6,
EXTI4_15 => PC7,
EXTI4_15 => PC8,
EXTI4_15 => PC9,
EXTI4_15 => PC10,
EXTI4_15 => PC11,
EXTI4_15 => PC12,
EXTI4_15 => PC13,
EXTI4_15 => PC14,
EXTI4_15 => PC15,
]);
exti!(gpiod, [
EXTI0_1 => PD0,
EXTI0_1 => PD1,
EXTI2_3 => PD2,
EXTI2_3 => PD3,
EXTI4_15 => PD4,
EXTI4_15 => PD5,
EXTI4_15 => PD6,
EXTI4_15 => PD7,
EXTI4_15 => PD8,
EXTI4_15 => PD9,
EXTI4_15 => PD10,
EXTI4_15 => PD11,
EXTI4_15 => PD12,
EXTI4_15 => PD13,
EXTI4_15 => PD14,
EXTI4_15 => PD15,
]);
exti!(gpioe, [
EXTI0_1 => PE0,
EXTI0_1 => PE1,
EXTI2_3 => PE2,
EXTI2_3 => PE3,
EXTI4_15 => PE4,
EXTI4_15 => PE5,
EXTI4_15 => PE6,
EXTI4_15 => PE7,
EXTI4_15 => PE8,
EXTI4_15 => PE9,
EXTI4_15 => PE10,
EXTI4_15 => PE11,
EXTI4_15 => PE12,
EXTI4_15 => PE13,
EXTI4_15 => PE14,
EXTI4_15 => PE15,
]);
exti!(gpioh, [
EXTI0_1 => PH0,
EXTI0_1 => PH1,
EXTI4_15 => PH9,
EXTI4_15 => PH10,
]);

View File

@ -19,6 +19,4 @@ compile_error!(
"Multile chip features activated. You must activate exactly one of the following features: "
);
pub use embassy_stm32::{fmt, hal, interrupt, pac};
pub mod exti;
pub use embassy_stm32::{exti, fmt, hal, interrupt, pac};

View File

@ -4,6 +4,9 @@ use core::pin::Pin;
pub trait Delay {
type DelayFuture<'a>: Future<Output = ()> + 'a;
/// Future that completes after now + millis
fn delay_ms<'a>(self: Pin<&'a mut Self>, millis: u64) -> Self::DelayFuture<'a>;
/// Future that completes after now + micros
fn delay_us<'a>(self: Pin<&'a mut Self>, micros: u64) -> Self::DelayFuture<'a>;
}

View File

@ -10,6 +10,15 @@ pub enum Error {
pub trait Uart {
type ReceiveFuture<'a>: Future<Output = Result<(), Error>>;
type SendFuture<'a>: Future<Output = Result<(), Error>>;
/// Receive into the buffer until the buffer is full
fn receive<'a>(&'a mut self, buf: &'a mut [u8]) -> Self::ReceiveFuture<'a>;
/// Send the specified buffer, and return when the transmission has completed
fn send<'a>(&'a mut self, buf: &'a [u8]) -> Self::SendFuture<'a>;
}
pub trait IdleUart {
type ReceiveFuture<'a>: Future<Output = Result<usize, Error>>;
/// Receive into the buffer until the buffer is full or the line is idle after some bytes are received
/// Return the number of bytes received
fn receive_until_idle<'a>(&'a mut self, buf: &'a mut [u8]) -> Self::ReceiveFuture<'a>;
}

View File

@ -7,6 +7,7 @@ use futures::Stream;
use super::raw;
use crate::time::{Duration, Instant};
/// Delay abstraction using embassy's clock.
pub struct Delay {
_data: PhantomData<bool>,
}
@ -30,12 +31,14 @@ impl crate::traits::delay::Delay for Delay {
}
}
/// A future that completes at a specified [Instant](struct.Instant.html).
pub struct Timer {
expires_at: Instant,
yielded_once: bool,
}
impl Timer {
/// Expire at specified [Instant](struct.Instant.html)
pub fn at(expires_at: Instant) -> Self {
Self {
expires_at,
@ -43,6 +46,26 @@ impl Timer {
}
}
/// Expire after specified [Duration](struct.Duration.html).
/// This can be used as a `sleep` abstraction.
///
/// Example:
/// ``` no_run
/// # #![feature(trait_alias)]
/// # #![feature(min_type_alias_impl_trait)]
/// # #![feature(impl_trait_in_bindings)]
/// # #![feature(type_alias_impl_trait)]
/// #
/// # fn foo() {}
/// use embassy::executor::task;
/// use embassy::time::{Duration, Timer};
///
/// #[task]
/// async fn demo_sleep_seconds() {
/// // suspend this task for one second.
/// Timer::after(Duration::from_secs(1)).await;
/// }
/// ```
pub fn after(duration: Duration) -> Self {
Self {
expires_at: Instant::now() + duration,
@ -66,12 +89,62 @@ impl Future for Timer {
}
}
/// Asynchronous stream that yields every Duration, indefinitely.
///
/// This stream will tick at uniform intervals, even if blocking work is performed between ticks.
///
/// For instance, consider the following code fragment.
/// ``` no_run
/// # #![feature(trait_alias)]
/// # #![feature(min_type_alias_impl_trait)]
/// # #![feature(impl_trait_in_bindings)]
/// # #![feature(type_alias_impl_trait)]
/// #
/// use embassy::executor::task;
/// use embassy::time::{Duration, Timer};
/// # fn foo() {}
///
/// #[task]
/// async fn ticker_example_0() {
/// loop {
/// foo();
/// Timer::after(Duration::from_secs(1)).await;
/// }
/// }
/// ```
///
/// This fragment will not call `foo` every second.
/// Instead, it will call it every second + the time it took to previously call `foo`.
///
/// Example using ticker, which will consistently call `foo` once a second.
///
/// ``` no_run
/// # #![feature(trait_alias)]
/// # #![feature(min_type_alias_impl_trait)]
/// # #![feature(impl_trait_in_bindings)]
/// # #![feature(type_alias_impl_trait)]
/// #
/// use embassy::executor::task;
/// use embassy::time::{Duration, Ticker};
/// use futures::StreamExt;
/// # fn foo(){}
///
/// #[task]
/// async fn ticker_example_1() {
/// let mut ticker = Ticker::every(Duration::from_secs(1));
/// loop {
/// foo();
/// ticker.next().await;
/// }
/// }
/// ```
pub struct Ticker {
expires_at: Instant,
duration: Duration,
}
impl Ticker {
/// Creates a new ticker that ticks at the specified duration interval.
pub fn every(duration: Duration) -> Self {
let expires_at = Instant::now() + duration;
Self {

View File

@ -5,6 +5,7 @@ use super::TICKS_PER_SECOND;
#[derive(Debug, Default, Copy, Clone, PartialEq, Eq, PartialOrd, Ord)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
/// Represents the difference between two [Instant](struct.Instant.html)s
pub struct Duration {
pub(crate) ticks: u64,
}
@ -26,49 +27,55 @@ impl Duration {
self.ticks * 1_000_000 / TICKS_PER_SECOND
}
/// Creates a duration from the specified number of clock ticks
pub const fn from_ticks(ticks: u64) -> Duration {
Duration { ticks }
}
/// Creates a duration from the specified number of seconds
pub const fn from_secs(secs: u64) -> Duration {
Duration {
ticks: secs * TICKS_PER_SECOND,
}
}
/// Creates a duration from the specified number of milliseconds
pub const fn from_millis(millis: u64) -> Duration {
Duration {
ticks: millis * TICKS_PER_SECOND / 1000,
}
}
/*
NOTE: us delays may not be as accurate
*/
/// Creates a duration from the specified number of microseconds
/// NOTE: Delays this small may be inaccurate.
pub const fn from_micros(micros: u64) -> Duration {
Duration {
ticks: micros * TICKS_PER_SECOND / 1_000_000,
}
}
/// Adds one Duration to another, returning a new Duration or None in the event of an overflow.
pub fn checked_add(self, rhs: Duration) -> Option<Duration> {
self.ticks
.checked_add(rhs.ticks)
.map(|ticks| Duration { ticks })
}
/// Subtracts one Duration to another, returning a new Duration or None in the event of an overflow.
pub fn checked_sub(self, rhs: Duration) -> Option<Duration> {
self.ticks
.checked_sub(rhs.ticks)
.map(|ticks| Duration { ticks })
}
/// Multiplies one Duration by a scalar u32, returning a new Duration or None in the event of an overflow.
pub fn checked_mul(self, rhs: u32) -> Option<Duration> {
self.ticks
.checked_mul(rhs as _)
.map(|ticks| Duration { ticks })
}
/// Divides one Duration a scalar u32, returning a new Duration or None in the event of an overflow.
pub fn checked_div(self, rhs: u32) -> Option<Duration> {
self.ticks
.checked_div(rhs as _)

View File

@ -6,6 +6,7 @@ use super::{now, Duration};
#[derive(Debug, Copy, Clone, PartialEq, Eq, PartialOrd, Ord)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
/// An Instant in time, based on the MCU's clock ticks since startup.
pub struct Instant {
ticks: u64,
}
@ -14,44 +15,55 @@ impl Instant {
pub const MIN: Instant = Instant { ticks: u64::MIN };
pub const MAX: Instant = Instant { ticks: u64::MAX };
/// Returns an Instant representing the current time.
pub fn now() -> Instant {
Instant { ticks: now() }
}
/// Instant as clock ticks since MCU start.
pub const fn from_ticks(ticks: u64) -> Self {
Self { ticks }
}
/// Instant as milliseconds since MCU start.
pub const fn from_millis(millis: u64) -> Self {
Self {
ticks: millis * TICKS_PER_SECOND as u64 / 1000,
}
}
/// Instant representing seconds since MCU start.
pub const fn from_secs(seconds: u64) -> Self {
Self {
ticks: seconds * TICKS_PER_SECOND as u64,
}
}
/// Instant as ticks since MCU start.
pub const fn as_ticks(&self) -> u64 {
self.ticks
}
/// Instant as seconds since MCU start.
pub const fn as_secs(&self) -> u64 {
self.ticks / TICKS_PER_SECOND as u64
}
/// Instant as miliseconds since MCU start.
pub const fn as_millis(&self) -> u64 {
self.ticks * 1000 / TICKS_PER_SECOND as u64
}
/// Duration between this Instant and another Instant
/// Panics on over/underflow.
pub fn duration_since(&self, earlier: Instant) -> Duration {
Duration {
ticks: self.ticks.checked_sub(earlier.ticks).unwrap(),
}
}
/// Duration between this Instant and another Instant
pub fn checked_duration_since(&self, earlier: Instant) -> Option<Duration> {
if self.ticks < earlier.ticks {
None
@ -62,6 +74,8 @@ impl Instant {
}
}
/// Returns the duration since the "earlier" Instant.
/// If the "earlier" instant is in the future, the duration is set to zero.
pub fn saturating_duration_since(&self, earlier: Instant) -> Duration {
Duration {
ticks: if self.ticks < earlier.ticks {
@ -72,6 +86,7 @@ impl Instant {
}
}
/// Duration elapsed since this Instant.
pub fn elapsed(&self) -> Duration {
Instant::now() - *self
}

View File

@ -1,3 +1,6 @@
//! Time abstractions
//! To use these abstractions, first call `set_clock` with an instance of an [Clock](trait.Clock.html).
//!
mod duration;
mod instant;
mod traits;
@ -14,10 +17,16 @@ pub const TICKS_PER_SECOND: u64 = 32768;
static mut CLOCK: Option<&'static dyn Clock> = None;
/// Sets the clock used for the timing abstractions
///
/// Safety: Sets a mutable global.
pub unsafe fn set_clock(clock: &'static dyn Clock) {
CLOCK = Some(clock);
}
/// Return the current timestamp in ticks.
/// This is guaranteed to be monotonic, i.e. a call to now() will always return
/// a greater or equal value than earler calls.
pub(crate) fn now() -> u64 {
unsafe { unwrap!(CLOCK, "No clock set").now() }
}

View File

@ -1,6 +1,12 @@
use crate::fmt::panic;
use core::mem;
/// An explosive ordinance that panics if it is improperly disposed of.
///
/// This is to forbid dropping futures, when there is absolutely no other choice.
///
/// To correctly dispose of this device, call the [defuse](struct.DropBomb.html#method.defuse)
/// method before this object is dropped.
pub struct DropBomb {
_private: (),
}
@ -10,6 +16,7 @@ impl DropBomb {
Self { _private: () }
}
/// Diffuses the bomb, rendering it safe to drop.
pub fn defuse(self) {
mem::forget(self)
}

View File

@ -3,6 +3,25 @@ use core::mem::MaybeUninit;
use atomic_polyfill::{AtomicBool, Ordering};
/// Type with static lifetime that may be written to once at runtime.
///
/// This may be used to initialize static objects at runtime, typically in the init routine.
/// This is useful for objects such as Embassy's RTC, which cannot be initialized in a const
/// context.
///
/// Note: IF a global mutable variable is desired, use a CriticalSectionMutex or ThreadModeMutex instead.
///
/// ```
/// use embassy::util::Forever;
/// // Using an integer for the sake of keeping this example self-contained,
/// // see https://github.com/embassy-rs/embassy/wiki/Getting-Started for a more "proper" example.
/// static SOME_INT: Forever<u32> =Forever::new();
///
/// // put returns a mutable pointer to the object stored in the forever, which may then be passed
/// // around.
/// let mut x = SOME_INT.put(42);
/// assert_eq!(*x, 42);
/// ```
pub struct Forever<T> {
used: AtomicBool,
t: UnsafeCell<MaybeUninit<T>>,
@ -19,6 +38,11 @@ impl<T> Forever<T> {
}
}
/// Gives this `Forever` a value.
///
/// Panics if this `Forever` already has a value.
///
/// Returns a mutable reference to the stored value.
pub fn put(&'static self, val: T) -> &'static mut T {
if self
.used

View File

@ -1,3 +1,4 @@
//! Async utilities
mod drop_bomb;
mod forever;
mod mutex;

View File

@ -10,6 +10,9 @@ use crate::executor;
use crate::fmt::panic;
use crate::interrupt::{Interrupt, InterruptExt};
/// Synchronization primitive. Allows creating awaitable signals that may be passed between tasks.
///
/// For more advanced use cases, please consider [futures-intrusive](https://crates.io/crates/futures-intrusive) channels or mutexes.
pub struct Signal<T> {
state: UnsafeCell<State<T>>,
}
@ -30,6 +33,7 @@ impl<T: Send> Signal<T> {
}
}
/// Mark this Signal as completed.
pub fn signal(&self, val: T) {
cortex_m::interrupt::free(|_| unsafe {
let state = &mut *self.state.get();
@ -64,10 +68,12 @@ impl<T: Send> Signal<T> {
})
}
/// Future that completes when this Signal has been signaled.
pub fn wait(&self) -> impl Future<Output = T> + '_ {
futures::future::poll_fn(move |cx| self.poll_wait(cx))
}
/// non-blocking method to check whether this signal has been signaled.
pub fn signaled(&self) -> bool {
cortex_m::interrupt::free(|_| matches!(unsafe { &*self.state.get() }, State::Signaled(_)))
}
@ -80,6 +86,25 @@ unsafe impl cortex_m::interrupt::Nr for NrWrap {
}
}
/// Creates a future that completes when the specified Interrupt is triggered.
///
/// The input handler is unregistered when this Future is dropped.
///
/// Example:
/// ``` no_compile
/// use embassy::traits::*;
/// use embassy::util::InterruptFuture;
/// use embassy::executor::task;
/// use embassy_stm32f4::interrupt; // Adjust this to your MCU's embassy HAL.
/// #[task]
/// async fn demo_interrupt_future() {
/// // Using STM32f446 interrupt names, adjust this to your application as necessary.
/// // Wait for TIM2 to tick.
/// let mut tim2_interrupt = interrupt::take!(TIM2);
/// InterruptFuture::new(&mut tim2_interrupt).await;
/// // TIM2 interrupt went off, do something...
/// }
/// ```
pub struct InterruptFuture<'a, I: Interrupt> {
interrupt: &'a mut I,
}