summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--.github/workflows/rust.yml2
-rw-r--r--embassy-macros/src/chip/nrf.rs13
-rw-r--r--embassy-macros/src/chip/rp.rs8
-rw-r--r--embassy-macros/src/chip/stm32.rs17
-rw-r--r--embassy-nrf/src/lib.rs8
-rw-r--r--embassy-nrf/src/time_driver.rs (renamed from embassy-nrf/src/rtc.rs)239
-rw-r--r--embassy-rp/Cargo.toml2
-rw-r--r--embassy-rp/src/lib.rs5
-rw-r--r--embassy-rp/src/timer.rs72
-rw-r--r--embassy-std/src/lib.rs38
-rw-r--r--embassy-stm32/src/clock.rs372
-rw-r--r--embassy-stm32/src/lib.rs6
-rw-r--r--embassy-stm32/src/time_driver.rs319
-rw-r--r--embassy/src/executor/mod.rs12
-rw-r--r--embassy/src/executor/raw.rs37
-rw-r--r--embassy/src/time/driver.rs118
-rw-r--r--embassy/src/time/instant.rs7
-rw-r--r--embassy/src/time/mod.rs22
-rw-r--r--embassy/src/time/traits.rs32
-rw-r--r--examples/nrf/src/bin/blinky.rs1
-rw-r--r--examples/nrf/src/bin/executor_fairness_test.rs3
-rw-r--r--examples/nrf/src/bin/gpiote_channel.rs3
-rw-r--r--examples/nrf/src/bin/gpiote_port.rs2
-rw-r--r--examples/nrf/src/bin/mpsc.rs1
-rw-r--r--examples/nrf/src/bin/multiprio.rs18
-rw-r--r--examples/nrf/src/bin/ppi.rs3
-rw-r--r--examples/nrf/src/bin/pwm.rs4
-rw-r--r--examples/nrf/src/bin/raw_spawn.rs15
-rw-r--r--examples/nrf/src/bin/timer.rs1
-rw-r--r--examples/stm32f4/src/bin/blinky.rs1
-rw-r--r--examples/stm32f4/src/bin/button_exti.rs1
-rw-r--r--examples/stm32f4/src/bin/hello.rs2
-rw-r--r--examples/stm32f4/src/bin/spi_dma.rs1
-rw-r--r--examples/stm32f4/src/bin/usart_dma.rs1
-rw-r--r--examples/stm32h7/src/bin/blinky.rs17
-rw-r--r--examples/stm32h7/src/bin/eth.rs13
-rw-r--r--examples/stm32h7/src/bin/spi.rs10
-rw-r--r--examples/stm32h7/src/bin/spi_dma.rs10
-rw-r--r--examples/stm32h7/src/bin/usart.rs11
-rw-r--r--examples/stm32h7/src/bin/usart_dma.rs11
-rw-r--r--examples/stm32l0/src/bin/blinky.rs1
-rw-r--r--examples/stm32l0/src/bin/button_exti.rs1
-rw-r--r--examples/stm32l0/src/bin/usart_dma.rs1
-rw-r--r--examples/stm32l4/src/bin/blinky.rs1
-rw-r--r--examples/stm32l4/src/bin/button_exti.rs1
-rw-r--r--examples/stm32l4/src/bin/spi_dma.rs1
-rw-r--r--examples/stm32l4/src/bin/usart_dma.rs1
47 files changed, 657 insertions, 808 deletions
diff --git a/.github/workflows/rust.yml b/.github/workflows/rust.yml
index d11bc8d4..38d9c128 100644
--- a/.github/workflows/rust.yml
+++ b/.github/workflows/rust.yml
@@ -77,7 +77,7 @@ jobs:
features: stm32l476vg,defmt
- package: embassy-stm32
target: thumbv6m-none-eabi
- features: stm32l053r8,defmt
+ features: stm32l072cz,defmt
- package: examples/stm32f4
target: thumbv7em-none-eabi
- package: examples/stm32l4
diff --git a/embassy-macros/src/chip/nrf.rs b/embassy-macros/src/chip/nrf.rs
index 503a8ba5..3ff6a74c 100644
--- a/embassy-macros/src/chip/nrf.rs
+++ b/embassy-macros/src/chip/nrf.rs
@@ -3,22 +3,9 @@ use proc_macro2::TokenStream;
use quote::quote;
pub fn generate(embassy_prefix: &ModulePrefix, config: syn::Expr) -> TokenStream {
- let embassy_path = embassy_prefix.append("embassy").path();
let embassy_nrf_path = embassy_prefix.append("embassy_nrf").path();
quote!(
- use #embassy_nrf_path::{interrupt, peripherals, rtc};
-
let p = #embassy_nrf_path::init(#config);
-
- let mut rtc = rtc::RTC::new(unsafe { <peripherals::RTC1 as #embassy_path::util::Steal>::steal() }, interrupt::take!(RTC1));
- let rtc = unsafe { make_static(&mut rtc) };
- rtc.start();
- let mut alarm = rtc.alarm0();
-
- unsafe { #embassy_path::time::set_clock(rtc) };
-
- let alarm = unsafe { make_static(&mut alarm) };
- executor.set_alarm(alarm);
)
}
diff --git a/embassy-macros/src/chip/rp.rs b/embassy-macros/src/chip/rp.rs
index d40a4496..ba0a97ad 100644
--- a/embassy-macros/src/chip/rp.rs
+++ b/embassy-macros/src/chip/rp.rs
@@ -3,16 +3,8 @@ use proc_macro2::TokenStream;
use quote::quote;
pub fn generate(embassy_prefix: &ModulePrefix, config: syn::Expr) -> TokenStream {
- let embassy_path = embassy_prefix.append("embassy").path();
let embassy_rp_path = embassy_prefix.append("embassy_rp").path();
quote!(
- use #embassy_rp_path::{interrupt, peripherals};
-
let p = #embassy_rp_path::init(#config);
-
- let alarm = unsafe { <#embassy_rp_path::peripherals::TIMER_ALARM0 as #embassy_path::util::Steal>::steal() };
- let mut alarm = #embassy_rp_path::timer::Alarm::new(alarm);
- let alarm = unsafe { make_static(&mut alarm) };
- executor.set_alarm(alarm);
)
}
diff --git a/embassy-macros/src/chip/stm32.rs b/embassy-macros/src/chip/stm32.rs
index 32a0a017..c6938836 100644
--- a/embassy-macros/src/chip/stm32.rs
+++ b/embassy-macros/src/chip/stm32.rs
@@ -3,26 +3,9 @@ use proc_macro2::TokenStream;
use quote::quote;
pub fn generate(embassy_prefix: &ModulePrefix, config: syn::Expr) -> TokenStream {
- let embassy_path = embassy_prefix.append("embassy").path();
let embassy_stm32_path = embassy_prefix.append("embassy_stm32").path();
quote!(
- use #embassy_stm32_path::{interrupt, peripherals, clock::Clock, time::Hertz};
-
let p = #embassy_stm32_path::init(#config);
-
- let mut c = Clock::new(
- unsafe { <peripherals::TIM3 as embassy::util::Steal>::steal() },
- interrupt::take!(TIM3),
- );
- let clock = unsafe { make_static(&mut c) };
-
- clock.start();
-
- let mut alarm = clock.alarm1();
- unsafe { #embassy_path::time::set_clock(clock) };
-
- let alarm = unsafe { make_static(&mut alarm) };
- executor.set_alarm(alarm);
)
}
diff --git a/embassy-nrf/src/lib.rs b/embassy-nrf/src/lib.rs
index 9054ba89..4cce8028 100644
--- a/embassy-nrf/src/lib.rs
+++ b/embassy-nrf/src/lib.rs
@@ -23,6 +23,8 @@ compile_error!("No chip feature activated. You must activate exactly one of the
pub(crate) mod fmt;
pub(crate) mod util;
+mod time_driver;
+
pub mod buffered_uarte;
pub mod gpio;
pub mod gpiote;
@@ -32,7 +34,6 @@ pub mod pwm;
#[cfg(feature = "nrf52840")]
pub mod qspi;
pub mod rng;
-pub mod rtc;
#[cfg(not(feature = "nrf52820"))]
pub mod saadc;
pub mod spim;
@@ -160,7 +161,10 @@ pub fn init(config: config::Config) -> Peripherals {
while r.events_lfclkstarted.read().bits() == 0 {}
// Init GPIOTE
- crate::gpiote::init(config.gpiote_interrupt_priority);
+ gpiote::init(config.gpiote_interrupt_priority);
+
+ // init RTC time driver
+ time_driver::init();
peripherals
}
diff --git a/embassy-nrf/src/rtc.rs b/embassy-nrf/src/time_driver.rs
index 99b6c099..7815427e 100644
--- a/embassy-nrf/src/rtc.rs
+++ b/embassy-nrf/src/time_driver.rs
@@ -1,13 +1,17 @@
use core::cell::Cell;
-use core::sync::atomic::{compiler_fence, AtomicU32, Ordering};
+use core::sync::atomic::{compiler_fence, AtomicU32, AtomicU8, Ordering};
+use core::{mem, ptr};
use critical_section::CriticalSection;
-use embassy::interrupt::InterruptExt;
-use embassy::time::Clock;
-use embassy::util::{CriticalSectionMutex as Mutex, Unborrow};
+use embassy::interrupt::{Interrupt, InterruptExt};
+use embassy::time::driver::{AlarmHandle, Driver};
+use embassy::util::CriticalSectionMutex as Mutex;
-use crate::interrupt::Interrupt;
+use crate::interrupt;
use crate::pac;
-use crate::{interrupt, peripherals};
+
+fn rtc() -> &'static pac::rtc0::RegisterBlock {
+ unsafe { &*pac::RTC1::ptr() }
+}
// RTC timekeeping works with something we call "periods", which are time intervals
// of 2^23 ticks. The RTC counter value is 24 bits, so one "overflow cycle" is 2 periods.
@@ -57,46 +61,45 @@ mod test {
struct AlarmState {
timestamp: Cell<u64>,
- callback: Cell<Option<(fn(*mut ()), *mut ())>>,
+
+ // This is really a Option<(fn(*mut ()), *mut ())>
+ // but fn pointers aren't allowed in const yet
+ callback: Cell<*const ()>,
+ ctx: Cell<*mut ()>,
}
+unsafe impl Send for AlarmState {}
+
impl AlarmState {
- fn new() -> Self {
+ const fn new() -> Self {
Self {
timestamp: Cell::new(u64::MAX),
- callback: Cell::new(None),
+ callback: Cell::new(ptr::null()),
+ ctx: Cell::new(ptr::null_mut()),
}
}
}
const ALARM_COUNT: usize = 3;
-pub struct RTC<T: Instance> {
- rtc: T,
- irq: T::Interrupt,
-
+struct State {
/// Number of 2^23 periods elapsed since boot.
period: AtomicU32,
-
+ alarm_count: AtomicU8,
/// Timestamp at which to fire alarm. u64::MAX if no alarm is scheduled.
alarms: Mutex<[AlarmState; ALARM_COUNT]>,
}
-unsafe impl<T: Instance> Send for RTC<T> {}
-unsafe impl<T: Instance> Sync for RTC<T> {}
+const ALARM_STATE_NEW: AlarmState = AlarmState::new();
+static STATE: State = State {
+ period: AtomicU32::new(0),
+ alarm_count: AtomicU8::new(0),
+ alarms: Mutex::new([ALARM_STATE_NEW; ALARM_COUNT]),
+};
-impl<T: Instance> RTC<T> {
- pub fn new(rtc: T, irq: T::Interrupt) -> Self {
- Self {
- rtc,
- irq,
- period: AtomicU32::new(0),
- alarms: Mutex::new([AlarmState::new(), AlarmState::new(), AlarmState::new()]),
- }
- }
-
- pub fn start(&'static self) {
- let r = self.rtc.regs();
+impl State {
+ fn init(&'static self) {
+ let r = rtc();
r.cc[3].write(|w| unsafe { w.bits(0x800000) });
r.intenset.write(|w| {
@@ -111,17 +114,11 @@ impl<T: Instance> RTC<T> {
// Wait for clear
while r.counter.read().bits() != 0 {}
- self.irq.set_handler(|ptr| unsafe {
- let this = &*(ptr as *const () as *const Self);
- this.on_interrupt();
- });
- self.irq.set_handler_context(self as *const _ as *mut _);
- self.irq.unpend();
- self.irq.enable();
+ unsafe { interrupt::RTC1::steal() }.enable();
}
fn on_interrupt(&self) {
- let r = self.rtc.regs();
+ let r = rtc();
if r.events_ovrflw.read().bits() == 1 {
r.events_ovrflw.write(|w| w);
self.next_period();
@@ -144,7 +141,7 @@ impl<T: Instance> RTC<T> {
fn next_period(&self) {
critical_section::with(|cs| {
- let r = self.rtc.regs();
+ let r = rtc();
let period = self.period.fetch_add(1, Ordering::Relaxed) + 1;
let t = (period as u64) << 23;
@@ -152,38 +149,77 @@ impl<T: Instance> RTC<T> {
let alarm = &self.alarms.borrow(cs)[n];
let at = alarm.timestamp.get();
- let diff = at - t;
- if diff < 0xc00000 {
- r.cc[n].write(|w| unsafe { w.bits(at as u32 & 0xFFFFFF) });
+ if at < t + 0xc00000 {
+ // just enable it. `set_alarm` has already set the correct CC val.
r.intenset.write(|w| unsafe { w.bits(compare_n(n)) });
}
}
})
}
+ fn now(&self) -> u64 {
+ // `period` MUST be read before `counter`, see comment at the top for details.
+ let period = self.period.load(Ordering::Relaxed);
+ compiler_fence(Ordering::Acquire);
+ let counter = rtc().counter.read().bits();
+ calc_now(period, counter)
+ }
+
+ fn get_alarm<'a>(&'a self, cs: CriticalSection<'a>, alarm: AlarmHandle) -> &'a AlarmState {
+ // safety: we're allowed to assume the AlarmState is created by us, and
+ // we never create one that's out of bounds.
+ unsafe { self.alarms.borrow(cs).get_unchecked(alarm.id() as usize) }
+ }
+
fn trigger_alarm(&self, n: usize, cs: CriticalSection) {
- let r = self.rtc.regs();
+ let r = rtc();
r.intenclr.write(|w| unsafe { w.bits(compare_n(n)) });
let alarm = &self.alarms.borrow(cs)[n];
alarm.timestamp.set(u64::MAX);
// Call after clearing alarm, so the callback can set another alarm.
- if let Some((f, ctx)) = alarm.callback.get() {
- f(ctx);
+
+ // safety:
+ // - we can ignore the possiblity of `f` being unset (null) because of the safety contract of `allocate_alarm`.
+ // - other than that we only store valid function pointers into alarm.callback
+ let f: fn(*mut ()) = unsafe { mem::transmute(alarm.callback.get()) };
+ f(alarm.ctx.get());
+ }
+
+ fn allocate_alarm(&self) -> Option<AlarmHandle> {
+ let id = self
+ .alarm_count
+ .fetch_update(Ordering::AcqRel, Ordering::Acquire, |x| {
+ if x < ALARM_COUNT as u8 {
+ Some(x + 1)
+ } else {
+ None
+ }
+ });
+
+ match id {
+ Ok(id) => Some(unsafe { AlarmHandle::new(id) }),
+ Err(_) => None,
}
}
- fn set_alarm_callback(&self, n: usize, callback: fn(*mut ()), ctx: *mut ()) {
+ fn set_alarm_callback(&self, alarm: AlarmHandle, callback: fn(*mut ()), ctx: *mut ()) {
critical_section::with(|cs| {
- let alarm = &self.alarms.borrow(cs)[n];
- alarm.callback.set(Some((callback, ctx)));
+ let alarm = self.get_alarm(cs, alarm);
+
+ // safety: it's OK to transmute a fn pointer into a raw pointer
+ let callback_ptr: *const () = unsafe { mem::transmute(callback) };
+
+ alarm.callback.set(callback_ptr);
+ alarm.ctx.set(ctx);
})
}
- fn set_alarm(&self, n: usize, timestamp: u64) {
+ fn set_alarm(&self, alarm: AlarmHandle, timestamp: u64) {
critical_section::with(|cs| {
- let alarm = &self.alarms.borrow(cs)[n];
+ let n = alarm.id() as _;
+ let alarm = self.get_alarm(cs, alarm);
alarm.timestamp.set(timestamp);
let t = self.now();
@@ -194,25 +230,30 @@ impl<T: Instance> RTC<T> {
return;
}
- let r = self.rtc.regs();
+ let r = rtc();
// If it hasn't triggered yet, setup it in the compare channel.
+
+ // Write the CC value regardless of whether we're going to enable it now or not.
+ // This way, when we enable it later, the right value is already set.
+
+ // nrf52 docs say:
+ // If the COUNTER is N, writing N or N+1 to a CC register may not trigger a COMPARE event.
+ // To workaround this, we never write a timestamp smaller than N+3.
+ // N+2 is not safe because rtc can tick from N to N+1 between calling now() and writing cc.
+ //
+ // It is impossible for rtc to tick more than once because
+ // - this code takes less time than 1 tick
+ // - it runs with interrupts disabled so nothing else can preempt it.
+ //
+ // This means that an alarm can be delayed for up to 2 ticks (from t+1 to t+3), but this is allowed
+ // by the Alarm trait contract. What's not allowed is triggering alarms *before* their scheduled time,
+ // and we don't do that here.
+ let safe_timestamp = timestamp.max(t + 3);
+ r.cc[n].write(|w| unsafe { w.bits(safe_timestamp as u32 & 0xFFFFFF) });
+
let diff = timestamp - t;
if diff < 0xc00000 {
- // nrf52 docs say:
- // If the COUNTER is N, writing N or N+1 to a CC register may not trigger a COMPARE event.
- // To workaround this, we never write a timestamp smaller than N+3.
- // N+2 is not safe because rtc can tick from N to N+1 between calling now() and writing cc.
- //
- // It is impossible for rtc to tick more than once because
- // - this code takes less time than 1 tick
- // - it runs with interrupts disabled so nothing else can preempt it.
- //
- // This means that an alarm can be delayed for up to 2 ticks (from t+1 to t+3), but this is allowed
- // by the Alarm trait contract. What's not allowed is triggering alarms *before* their scheduled time,
- // and we don't do that here.
- let safe_timestamp = timestamp.max(t + 3);
- r.cc[n].write(|w| unsafe { w.bits(safe_timestamp as u32 & 0xFFFFFF) });
r.intenset.write(|w| unsafe { w.bits(compare_n(n)) });
} else {
// If it's too far in the future, don't setup the compare channel yet.
@@ -221,74 +262,34 @@ impl<T: Instance> RTC<T> {
}
})
}
-
- pub fn alarm0(&'static self) -> Alarm<T> {
- Alarm { n: 0, rtc: self }
- }
- pub fn alarm1(&'static self) -> Alarm<T> {
- Alarm { n: 1, rtc: self }
- }
- pub fn alarm2(&'static self) -> Alarm<T> {
- Alarm { n: 2, rtc: self }
- }
-}
-
-impl<T: Instance> embassy::time::Clock for RTC<T> {
- fn now(&self) -> u64 {
- // `period` MUST be read before `counter`, see comment at the top for details.
- let period = self.period.load(Ordering::Relaxed);
- compiler_fence(Ordering::Acquire);
- let counter = self.rtc.regs().counter.read().bits();
- calc_now(period, counter)
- }
}
-pub struct Alarm<T: Instance> {
- n: usize,
- rtc: &'static RTC<T>,
-}
+struct RtcDriver;
+embassy::time_driver_impl!(RtcDriver);
-impl<T: Instance> embassy::time::Alarm for Alarm<T> {
- fn set_callback(&self, callback: fn(*mut ()), ctx: *mut ()) {
- self.rtc.set_alarm_callback(self.n, callback, ctx);
+impl Driver for RtcDriver {
+ fn now() -> u64 {
+ STATE.now()
}
- fn set(&self, timestamp: u64) {
- self.rtc.set_alarm(self.n, timestamp);
+ unsafe fn allocate_alarm() -> Option<AlarmHandle> {
+ STATE.allocate_alarm()
}
- fn clear(&self) {
- self.rtc.set_alarm(self.n, u64::MAX);
+ fn set_alarm_callback(alarm: AlarmHandle, callback: fn(*mut ()), ctx: *mut ()) {
+ STATE.set_alarm_callback(alarm, callback, ctx)
}
-}
-mod sealed {
- use super::*;
- pub trait Instance {
- fn regs(&self) -> &pac::rtc0::RegisterBlock;
+ fn set_alarm(alarm: AlarmHandle, timestamp: u64) {
+ STATE.set_alarm(alarm, timestamp)
}
}
-macro_rules! impl_instance {
- ($type:ident, $irq:ident) => {
- impl sealed::Instance for peripherals::$type {
- fn regs(&self) -> &pac::rtc0::RegisterBlock {
- unsafe { &*pac::$type::ptr() }
- }
- }
- impl Instance for peripherals::$type {
- type Interrupt = interrupt::$irq;
- }
- };
+#[interrupt]
+fn RTC1() {
+ STATE.on_interrupt()
}
-/// Implemented by all RTC instances.
-pub trait Instance: Unborrow<Target = Self> + sealed::Instance + 'static {
- /// The interrupt associated with this RTC instance.
- type Interrupt: Interrupt;
+pub(crate) fn init() {
+ STATE.init()
}
-
-impl_instance!(RTC0, RTC0);
-impl_instance!(RTC1, RTC1);
-#[cfg(any(feature = "nrf52832", feature = "nrf52833", feature = "nrf52840"))]
-impl_instance!(RTC2, RTC2);
diff --git a/embassy-rp/Cargo.toml b/embassy-rp/Cargo.toml
index e2da226d..5f078407 100644
--- a/embassy-rp/Cargo.toml
+++ b/embassy-rp/Cargo.toml
@@ -22,7 +22,7 @@ defmt-error = [ ]
embassy = { version = "0.1.0", path = "../embassy", features = [ "time-tick-1mhz" ] }
embassy-hal-common = {version = "0.1.0", path = "../embassy-hal-common" }
embassy-macros = { version = "0.1.0", path = "../embassy-macros", features = ["rp"]}
-
+atomic-polyfill = { version = "0.1.2" }
defmt = { version = "0.2.0", optional = true }
log = { version = "0.4.11", optional = true }
cortex-m-rt = "0.6.13"
diff --git a/embassy-rp/src/lib.rs b/embassy-rp/src/lib.rs
index 10bf7158..26ebbebf 100644
--- a/embassy-rp/src/lib.rs
+++ b/embassy-rp/src/lib.rs
@@ -69,11 +69,6 @@ embassy_hal_common::peripherals! {
SPI0,
SPI1,
- TIMER_ALARM0,
- TIMER_ALARM1,
- TIMER_ALARM2,
- TIMER_ALARM3,
-
DMA_CH0,
DMA_CH1,
DMA_CH2,
diff --git a/embassy-rp/src/timer.rs b/embassy-rp/src/timer.rs
index 5baa0260..71c59ec8 100644
--- a/embassy-rp/src/timer.rs
+++ b/embassy-rp/src/timer.rs
@@ -1,6 +1,8 @@
+use atomic_polyfill::{AtomicU8, Ordering};
use core::cell::Cell;
use critical_section::CriticalSection;
use embassy::interrupt::{Interrupt, InterruptExt};
+use embassy::time::driver::{AlarmHandle, Driver};
use embassy::util::CriticalSectionMutex as Mutex;
use crate::{interrupt, pac};
@@ -18,6 +20,7 @@ const DUMMY_ALARM: AlarmState = AlarmState {
};
static ALARMS: Mutex<[AlarmState; ALARM_COUNT]> = Mutex::new([DUMMY_ALARM; ALARM_COUNT]);
+static NEXT_ALARM: AtomicU8 = AtomicU8::new(0);
fn now() -> u64 {
loop {
@@ -32,60 +35,39 @@ fn now() -> u64 {
}
}
-struct Timer;
-impl embassy::time::Clock for Timer {
- fn now(&self) -> u64 {
- now()
- }
-}
+struct TimerDriver;
+embassy::time_driver_impl!(TimerDriver);
-pub trait AlarmInstance {
- fn alarm_num(&self) -> usize;
-}
-
-impl AlarmInstance for crate::peripherals::TIMER_ALARM0 {
- fn alarm_num(&self) -> usize {
- 0
- }
-}
-impl AlarmInstance for crate::peripherals::TIMER_ALARM1 {
- fn alarm_num(&self) -> usize {
- 1
- }
-}
-impl AlarmInstance for crate::peripherals::TIMER_ALARM2 {
- fn alarm_num(&self) -> usize {
- 2
- }
-}
-impl AlarmInstance for crate::peripherals::TIMER_ALARM3 {
- fn alarm_num(&self) -> usize {
- 3
+impl Driver for TimerDriver {
+ fn now() -> u64 {
+ now()
}
-}
-pub struct Alarm<T: AlarmInstance> {
- inner: T,
-}
+ unsafe fn allocate_alarm() -> Option<AlarmHandle> {
+ let id = NEXT_ALARM.fetch_update(Ordering::AcqRel, Ordering::Acquire, |x| {
+ if x < ALARM_COUNT as u8 {
+ Some(x + 1)
+ } else {
+ None
+ }
+ });
-impl<T: AlarmInstance> Alarm<T> {
- pub fn new(inner: T) -> Self {
- Self { inner }
+ match id {
+ Ok(id) => Some(AlarmHandle::new(id)),
+ Err(_) => None,
+ }
}
-}
-impl<T: AlarmInstance> embassy::time::Alarm for Alarm<T> {
- fn set_callback(&self, callback: fn(*mut ()), ctx: *mut ()) {
- let n = self.inner.alarm_num();
+ fn set_alarm_callback(alarm: AlarmHandle, callback: fn(*mut ()), ctx: *mut ()) {
+ let n = alarm.id() as usize;
critical_section::with(|cs| {
let alarm = &ALARMS.borrow(cs)[n];
alarm.callback.set(Some((callback, ctx)));
})
}
- fn set(&self, timestamp: u64) {
- let n = self.inner.alarm_num();
-
+ fn set_alarm(alarm: AlarmHandle, timestamp: u64) {
+ let n = alarm.id() as usize;
critical_section::with(|cs| {
let alarm = &ALARMS.borrow(cs)[n];
alarm.timestamp.set(timestamp);
@@ -105,10 +87,6 @@ impl<T: AlarmInstance> embassy::time::Alarm for Alarm<T> {
}
})
}
-
- fn clear(&self) {
- self.set(u64::MAX);
- }
}
fn check_alarm(n: usize) {
@@ -162,8 +140,6 @@ pub unsafe fn init() {
interrupt::TIMER_IRQ_1::steal().enable();
interrupt::TIMER_IRQ_2::steal().enable();
interrupt::TIMER_IRQ_3::steal().enable();
-
- embassy::time::set_clock(&Timer);
}
#[interrupt]
diff --git a/embassy-std/src/lib.rs b/embassy-std/src/lib.rs
index 688054cb..d85137e9 100644
--- a/embassy-std/src/lib.rs
+++ b/embassy-std/src/lib.rs
@@ -1,6 +1,6 @@
use embassy::executor::{raw, Spawner};
+use embassy::time::driver::{AlarmHandle, Driver};
use embassy::time::TICKS_PER_SECOND;
-use embassy::time::{Alarm, Clock};
use std::marker::PhantomData;
use std::mem::MaybeUninit;
use std::ptr;
@@ -8,28 +8,31 @@ use std::sync::{Condvar, Mutex};
use std::time::{Duration as StdDuration, Instant as StdInstant};
static mut CLOCK_ZERO: MaybeUninit<StdInstant> = MaybeUninit::uninit();
-struct StdClock;
-impl Clock for StdClock {
- fn now(&self) -> u64 {
+
+static mut ALARM_AT: u64 = u64::MAX;
+static mut NEXT_ALARM_ID: u8 = 0;
+
+struct TimeDriver;
+embassy::time_driver_impl!(TimeDriver);
+
+impl Driver for TimeDriver {
+ fn now() -> u64 {
let zero = unsafe { CLOCK_ZERO.as_ptr().read() };
let dur = StdInstant::now().duration_since(zero);
dur.as_secs() * (TICKS_PER_SECOND as u64)
+ (dur.subsec_nanos() as u64) * (TICKS_PER_SECOND as u64) / 1_000_000_000
}
-}
-static mut ALARM_AT: u64 = u64::MAX;
-
-pub struct StdAlarm;
-impl Alarm for StdAlarm {
- fn set_callback(&self, _callback: fn(*mut ()), _ctx: *mut ()) {}
-
- fn set(&self, timestamp: u64) {
- unsafe { ALARM_AT = timestamp }
+ unsafe fn allocate_alarm() -> Option<AlarmHandle> {
+ let r = NEXT_ALARM_ID;
+ NEXT_ALARM_ID += 1;
+ Some(AlarmHandle::new(r))
}
- fn clear(&self) {
- unsafe { ALARM_AT = u64::MAX }
+ fn set_alarm_callback(_alarm: AlarmHandle, _callback: fn(*mut ()), _ctx: *mut ()) {}
+
+ fn set_alarm(_alarm: AlarmHandle, timestamp: u64) {
+ unsafe { ALARM_AT = ALARM_AT.min(timestamp) }
}
}
@@ -53,7 +56,8 @@ impl Signaler {
if alarm_at == u64::MAX {
signaled = self.condvar.wait(signaled).unwrap();
} else {
- let now = StdClock.now();
+ unsafe { ALARM_AT = u64::MAX };
+ let now = TimeDriver::now();
if now >= alarm_at {
break;
}
@@ -92,7 +96,6 @@ impl Executor {
pub fn new() -> Self {
unsafe {
CLOCK_ZERO.as_mut_ptr().write(StdInstant::now());
- embassy::time::set_clock(&StdClock);
}
Self {
@@ -107,7 +110,6 @@ impl Executor {
/// This function never returns.
pub fn run(&'static mut self, init: impl FnOnce(Spawner)) -> ! {
self.inner.set_signal_ctx(&self.signaler as *const _ as _);
- self.inner.set_alarm(&StdAlarm);
init(unsafe { self.inner.spawner() });
diff --git a/embassy-stm32/src/clock.rs b/embassy-stm32/src/clock.rs
deleted file mode 100644
index 6c317578..00000000
--- a/embassy-stm32/src/clock.rs
+++ /dev/null
@@ -1,372 +0,0 @@
-#![macro_use]
-
-use core::cell::Cell;
-use core::convert::TryInto;
-use core::sync::atomic::{compiler_fence, Ordering};
-
-use atomic_polyfill::AtomicU32;
-use embassy::interrupt::InterruptExt;
-use embassy::time::{Clock as EmbassyClock, TICKS_PER_SECOND};
-
-use crate::interrupt::{CriticalSection, Interrupt, Mutex};
-use crate::pac::timer::TimGp16;
-use crate::peripherals;
-use crate::rcc::RccPeripheral;
-use crate::time::Hertz;
-
-// Clock timekeeping works with something we call "periods", which are time intervals
-// of 2^15 ticks. The Clock counter value is 16 bits, so one "overflow cycle" is 2 periods.
-//
-// A `period` count is maintained in parallel to the Timer hardware `counter`, like this:
-// - `period` and `counter` start at 0
-// - `period` is incremented on overflow (at counter value 0)
-// - `period` is incremented "midway" between overflows (at counter value 0x8000)
-//
-// Therefore, when `period` is even, counter is in 0..0x7FFF. When odd, counter is in 0x8000..0xFFFF
-// This allows for now() to return the correct value even if it races an overflow.
-//
-// To get `now()`, `period` is read first, then `counter` is read. If the counter value matches
-// the expected range for the `period` parity, we're done. If it doesn't, this means that
-// a new period start has raced us between reading `period` and `counter`, so we assume the `counter` value
-// corresponds to the next period.
-//
-// `period` is a 32bit integer, so It overflows on 2^32 * 2^15 / 32768 seconds of uptime, which is 136 years.
-fn calc_now(period: u32, counter: u16) -> u64 {
- ((period as u64) << 15) + ((counter as u32 ^ ((period & 1) << 15)) as u64)
-}
-
-struct AlarmState {
- timestamp: Cell<u64>,
- #[allow(clippy::type_complexity)]
- callback: Cell<Option<(fn(*mut ()), *mut ())>>,
-}
-
-impl AlarmState {
- fn new() -> Self {
- Self {
- timestamp: Cell::new(u64::MAX),
- callback: Cell::new(None),
- }
- }
-}
-
-const ALARM_COUNT: usize = 3;
-
-/// Clock timer that can be used by the executor and to set alarms.
-///
-/// It can work with Timers 2, 3, 4, 5. This timer works internally with a unit of 2^15 ticks, which
-/// means that if a call to [`embassy::time::Clock::now`] is blocked for that amount of ticks the
-/// returned value will be wrong (an old value). The current default tick rate is 32768 ticks per
-/// second.
-pub struct Clock<T: Instance> {
- _inner: T,
- irq: T::Interrupt,
- /// Number of 2^23 periods elapsed since boot.
- period: AtomicU32,
- /// Timestamp at which to fire alarm. u64::MAX if no alarm is scheduled.
- alarms: Mutex<[AlarmState; ALARM_COUNT]>,
-}
-
-impl<T: Instance> Clock<T> {
- pub fn new(peripheral: T, irq: T::Interrupt) -> Self {
- Self {
- _inner: peripheral,
- irq,
- period: AtomicU32::new(0),
- alarms: Mutex::new([AlarmState::new(), AlarmState::new(), AlarmState::new()]),
- }
- }
-
- pub fn start(&'static self) {
- let inner = T::inner();
-
- T::enable();
- T::reset();
-
- let timer_freq = T::frequency();
-
- // NOTE(unsafe) Critical section to use the unsafe methods
- critical_section::with(|_| {
- unsafe {
- inner.prepare(timer_freq);
- }
-
- self.irq.set_handler_context(self as *const _ as *mut _);
- self.irq.set_handler(|ptr| unsafe {
- let this = &*(ptr as *const () as *const Self);
- this.on_interrupt();
- });
- self.irq.unpend();
- self.irq.enable();
-
- unsafe {
- inner.start_counter();
- }
- })
- }
-
- fn on_interrupt(&self) {
- let inner = T::inner();
-
- // NOTE(unsafe) Use critical section to access the methods
- // XXX: reduce the size of this critical section ?
- critical_section::with(|cs| unsafe {
- if inner.overflow_interrupt_status() {
- inner.overflow_clear_flag();
- self.next_period();
- }
-
- // Half overflow
- if inner.compare_interrupt_status(0) {
- inner.compare_clear_flag(0);
- self.next_period();
- }
-
- for n in 1..=ALARM_COUNT {
- if inner.compare_interrupt_status(n) {
- inner.compare_clear_flag(n);
- self.trigger_alarm(n, cs);
- }
- }
- })
- }
-
- fn next_period(&self) {
- let inner = T::inner();
-
- let period = self.period.fetch_add(1, Ordering::Relaxed) + 1;
- let t = (period as u64) << 15;
-
- critical_section::with(move |cs| {
- for n in 1..=ALARM_COUNT {
- let alarm = &self.alarms.borrow(cs)[n - 1];
- let at = alarm.timestamp.get();
-
- let diff = at - t;
- if diff < 0xc000 {
- inner.set_compare(n, at as u16);
- // NOTE(unsafe) We're in a critical section
- unsafe {
- inner.set_compare_interrupt(n, true);
- }
- }
- }
- })
- }
-
- fn trigger_alarm(&self, n: usize, cs: CriticalSection) {
- let inner = T::inner();
- // NOTE(unsafe) We have a critical section
- unsafe {
- inner.set_compare_interrupt(n, false);
- }
-
- let alarm = &self.alarms.borrow(cs)[n - 1];
- alarm.timestamp.set(u64::MAX);
-
- // Call after clearing alarm, so the callback can set another alarm.
- if let Some((f, ctx)) = alarm.callback.get() {
- f(ctx);
- }
- }
-
- fn set_alarm_callback(&self, n: usize, callback: fn(*mut ()), ctx: *mut ()) {
- critical_section::with(|cs| {
- let alarm = &self.alarms.borrow(cs)[n - 1];
- alarm.callback.set(Some((callback, ctx)));
- })
- }
-
- fn set_alarm(&self, n: usize, timestamp: u64) {
- critical_section::with(|cs| {
- let inner = T::inner();
-
- let alarm = &self.alarms.borrow(cs)[n - 1];
- alarm.timestamp.set(timestamp);
-
- let t = self.now();
- if timestamp <= t {
- self.trigger_alarm(n, cs);
- return;
- }
-
- let diff = timestamp - t;
- if diff < 0xc000 {
- let safe_timestamp = timestamp.max(t + 3);
- inner.set_compare(n, safe_timestamp as u16);
-
- // NOTE(unsafe) We're in a critical section
- unsafe {
- inner.set_compare_interrupt(n, true);
- }
- } else {
- unsafe {
- inner.set_compare_interrupt(n, false);
- }
- }
- })
- }
-
- pub fn alarm1(&'static self) -> Alarm<T> {
- Alarm { n: 1, rtc: self }
- }
- pub fn alarm2(&'static self) -> Alarm<T> {
- Alarm { n: 2, rtc: self }
- }
- pub fn alarm3(&'static self) -> Alarm<T> {
- Alarm { n: 3, rtc: self }
- }
-}
-
-impl<T: Instance> EmbassyClock for Clock<T> {
- fn now(&self) -> u64 {
- let inner = T::inner();
-
- let period = self.period.load(Ordering::Relaxed);
- compiler_fence(Ordering::Acquire);
- let counter = inner.counter();
- calc_now(period, counter)
- }
-}
-
-pub struct Alarm<T: Instance> {
- n: usize,
- rtc: &'static Clock<T>,
-}
-
-impl<T: Instance> embassy::time::Alarm for Alarm<T> {
- fn set_callback(&self, callback: fn(*mut ()), ctx: *mut ()) {
- self.rtc.set_alarm_callback(self.n, callback, ctx);
- }
-
- fn set(&self, timestamp: u64) {
- self.rtc.set_alarm(self.n, timestamp);
- }
-
- fn clear(&self) {
- self.rtc.set_alarm(self.n, u64::MAX);
- }
-}
-
-pub struct TimerInner(pub(crate) TimGp16);
-
-impl TimerInner {
- unsafe fn prepare(&self, timer_freq: Hertz) {
- self.stop_and_reset();
-
- let psc = timer_freq.0 / TICKS_PER_SECOND as u32 - 1;
- let psc: u16 = psc.try_into().unwrap();
-
- self.set_psc_arr(psc, u16::MAX);
- // Mid-way point
- self.set_compare(0, 0x8000);
- self.set_compare_interrupt(0, true);
- }
-
- unsafe fn start_counter(&self) {
- self.0.cr1().modify(|w| w.set_cen(true));
- }
-
- unsafe fn stop_and_reset(&self) {
- let regs = self.0;
-
- regs.cr1().modify(|w| w.set_cen(false));
- regs.cnt().write(|w| w.set_cnt(0));
- }
-
- fn overflow_interrupt_status(&self) -> bool {
- // NOTE(unsafe) Atomic read with no side-effects
- unsafe { self.0.sr().read().uif() }
- }
-
- unsafe fn overflow_clear_flag(&self) {
- self.0.sr().modify(|w| w.set_uif(false));
- }
-
- unsafe fn set_psc_arr(&self, psc: u16, arr: u16) {
- use crate::pac::timer::vals::Urs;
-
- let regs = self.0;
-
- regs.psc().write(|w| w.set_psc(psc));
- regs.arr().write(|w| w.set_arr(arr));
-
- // Set URS, generate update and clear URS
- regs.cr1().modify(|w| w.set_urs(Urs::COUNTERONLY));
- regs.egr().write(|w| w.set_ug(true));
- regs.cr1().modify(|w| w.set_urs(Urs::ANYEVENT));
- }
-
- fn compare_interrupt_status(&self, n: usize) -> bool {
- if n > 3 {
- false
- } else {
- // NOTE(unsafe) Atomic read with no side-effects
- unsafe { self.0.sr().read().ccif(n) }
- }
- }
-
- unsafe fn compare_clear_flag(&self, n: usize) {
- if n > 3 {
- return;
- }
- self.0.sr().modify(|w| w.set_ccif(n, false));
- }
-
- fn set_compare(&self, n: usize, value: u16) {
- if n > 3 {
- return;
- }
- // NOTE(unsafe) Atomic write
- unsafe {
- self.0.ccr(n).write(|w| w.set_ccr(value));
- }
- }
-
- unsafe fn set_compare_interrupt(&self, n: usize, enable: bool) {
- if n > 3 {
- return;
- }
- self.0.dier().modify(|w| w.set_ccie(n, enable));
- }
-
- fn counter(&self) -> u16 {
- // NOTE(unsafe) Atomic read with no side-effects
- unsafe { self.0.cnt().read().cnt() }
- }
-}
-
-// ------------------------------------------------------
-
-pub(crate) mod sealed {
- use super::*;
- pub trait Instance {
- type Interrupt: Interrupt;
-
- fn inner() -> TimerInner;
- }
-}
-
-pub trait Instance: sealed::Instance + Sized + RccPeripheral + 'static {}
-
-macro_rules! impl_timer {
- ($inst:ident) => {
- impl sealed::Instance for peripherals::$inst {
- type Interrupt = crate::interrupt::$inst;
-
- fn inner() -> crate::clock::TimerInner {
- const INNER: TimerInner = TimerInner(crate::pac::$inst);
- INNER
- }
- }
-
- impl Instance for peripherals::$inst {}
- };
-}
-
-crate::pac::peripherals!(
- (timer, TIM2) => { impl_timer!(TIM2); };
- (timer, TIM3) => { impl_timer!(TIM3); };
- (timer, TIM4) => { impl_timer!(TIM4); };
- (timer, TIM5) => { impl_timer!(TIM5); };
-);
diff --git a/embassy-stm32/src/lib.rs b/embassy-stm32/src/lib.rs
index a58bc369..28bfcbaa 100644
--- a/embassy-stm32/src/lib.rs
+++ b/embassy-stm32/src/lib.rs
@@ -20,13 +20,12 @@ pub mod time;
pub mod dma;
pub mod gpio;
pub mod rcc;
+mod time_driver;
// Sometimes-present hardware
#[cfg(adc)]
pub mod adc;
-#[cfg(timer)]
-pub mod clock;
#[cfg(dac)]
pub mod dac;
#[cfg(dbgmcu)]
@@ -87,6 +86,9 @@ pub fn init(config: Config) -> Peripherals {
exti::init();
rcc::init(config.rcc);
+
+ // must be after rcc init
+ time_driver::init();
}
p
diff --git a/embassy-stm32/src/time_driver.rs b/embassy-stm32/src/time_driver.rs
new file mode 100644
index 00000000..16c871e8
--- /dev/null
+++ b/embassy-stm32/src/time_driver.rs
@@ -0,0 +1,319 @@
+use atomic_polyfill::{AtomicU32, AtomicU8};
+use core::cell::Cell;
+use core::convert::TryInto;
+use core::sync::atomic::{compiler_fence, Ordering};
+use core::{mem, ptr};
+use embassy::interrupt::InterruptExt;
+use embassy::time::driver::{AlarmHandle, Driver};
+use embassy::time::TICKS_PER_SECOND;
+use stm32_metapac::timer::regs;
+
+use crate::interrupt;
+use crate::interrupt::{CriticalSection, Interrupt, Mutex};
+use crate::pac::timer::{vals, TimGp16};
+use crate::peripherals;
+use crate::rcc::sealed::RccPeripheral;
+
+use self::sealed::Instance as _;
+
+const ALARM_COUNT: usize = 3;
+type T = peripherals::TIM3;
+
+// Clock timekeeping works with something we call "periods", which are time intervals
+// of 2^15 ticks. The Clock counter value is 16 bits, so one "overflow cycle" is 2 periods.
+//
+// A `period` count is maintained in parallel to the Timer hardware `counter`, like this:
+// - `period` and `counter` start at 0
+// - `period` is incremented on overflow (at counter value 0)
+// - `period` is incremented "midway" between overflows (at counter value 0x8000)
+//
+// Therefore, when `period` is even, counter is in 0..0x7FFF. When odd, counter is in 0x8000..0xFFFF
+// This allows for now() to return the correct value even if it races an overflow.
+//
+// To get `now()`, `period` is read first, then `counter` is read. If the counter value matches
+// the expected range for the `period` parity, we're done. If it doesn't, this means that
+// a new period start has raced us between reading `period` and `counter`, so we assume the `counter` value
+// corresponds to the next period.
+//
+// `period` is a 32bit integer, so It overflows on 2^32 * 2^15 / 32768 seconds of uptime, which is 136 years.
+fn calc_now(period: u32, counter: u16) -> u64 {
+ ((period as u64) << 15) + ((counter as u32 ^ ((period & 1) << 15)) as u64)
+}
+
+struct AlarmState {
+ timestamp: Cell<u64>,
+
+ // This is really a Option<(fn(*mut ()), *mut ())>
+ // but fn pointers aren't allowed in const yet
+ callback: Cell<*const ()>,
+ ctx: Cell<*mut ()>,
+}
+
+unsafe impl Send for AlarmState {}
+
+impl AlarmState {
+ const fn new() -> Self {
+ Self {
+ timestamp: Cell::new(u64::MAX),
+ callback: Cell::new(ptr::null()),
+ ctx: Cell::new(ptr::null_mut()),
+ }
+ }
+}
+
+struct State {
+ /// Number of 2^15 periods elapsed since boot.
+ period: AtomicU32,
+ alarm_count: AtomicU8,
+ /// Timestamp at which to fire alarm. u64::MAX if no alarm is scheduled.
+ alarms: Mutex<[AlarmState; ALARM_COUNT]>,
+}
+
+const ALARM_STATE_NEW: AlarmState = AlarmState::new();
+static STATE: State = State {
+ period: AtomicU32::new(0),
+ alarm_count: AtomicU8::new(0),
+ alarms: Mutex::new([ALARM_STATE_NEW; ALARM_COUNT]),
+};
+
+impl State {
+ fn init(&'static self) {
+ let r = T::regs();
+
+ T::enable();
+ T::reset();
+
+ let timer_freq = T::frequency();
+
+ // NOTE(unsafe) Critical section to use the unsafe methods
+ critical_section::with(|_| unsafe {
+ r.cr1().modify(|w| w.set_cen(false));
+ r.cnt().write(|w| w.set_cnt(0));
+
+ let psc = timer_freq.0 / TICKS_PER_SECOND as u32 - 1;
+ let psc: u16 = psc.try_into().unwrap();
+
+ r.psc().write(|w| w.set_psc(psc));
+ r.arr().write(|w| w.set_arr(u16::MAX));
+
+ // Set URS, generate update and clear URS
+ r.cr1().modify(|w| w.set_urs(vals::Urs::COUNTERONLY));
+ r.egr().write(|w| w.set_ug(true));
+ r.cr1().modify(|w| w.set_urs(vals::Urs::ANYEVENT));
+
+ // Mid-way point
+ r.ccr(0).write(|w| w.set_ccr(0x8000));
+
+ // Enable CC0, disable others
+ r.dier().write(|w| w.set_ccie(0, true));
+
+ let irq: <T as sealed::Instance>::Interrupt = core::mem::transmute(());
+ irq.unpend();
+ irq.enable();
+
+ r.cr1().modify(|w| w.set_cen(true));
+ })
+ }
+
+ fn on_interrupt(&self) {
+ let r = T::regs();
+
+ // NOTE(unsafe) Use critical section to access the methods
+ // XXX: reduce the size of this critical section ?
+ critical_section::with(|cs| unsafe {
+ let sr = r.sr().read();
+ let dier = r.dier().read();
+
+ // Clear all interrupt flags. Bits in SR are "write 0 to clear", so write the bitwise NOT.
+ // Other approaches such as writing all zeros, or RMWing won't work, they can
+ // miss interrupts.
+ r.sr().write_value(regs::SrGp(!sr.0));
+
+ if sr.uif() {
+ self.next_period();
+ }
+
+ // Half overflow
+ if sr.ccif(0) {
+ self.next_period();
+ }
+
+ for n in 0..ALARM_COUNT {
+ if sr.ccif(n + 1) && dier.ccie(n + 1) {
+ self.trigger_alarm(n, cs);
+ }
+ }
+ })
+ }
+
+ fn next_period(&self) {
+ let r = T::regs();
+
+ let period = self.period.fetch_add(1, Ordering::Relaxed) + 1;
+ let t = (period as u64) << 15;
+
+ critical_section::with(move |cs| unsafe {
+ r.dier().modify(move |w| {
+ for n in 0..ALARM_COUNT {
+ let alarm = &self.alarms.borrow(cs)[n];
+ let at = alarm.timestamp.get();
+
+ if at < t + 0xc000 {
+ // just enable it. `set_alarm` has already set the correct CCR val.
+ w.set_ccie(n + 1, true);
+ }
+ }
+ })
+ })
+ }
+
+ fn now(&self) -> u64 {
+ let r = T::regs();
+
+ let period = self.period.load(Ordering::Relaxed);
+ compiler_fence(Ordering::Acquire);
+ // NOTE(unsafe) Atomic read with no side-effects
+ let counter = unsafe { r.cnt().read().cnt() };
+ calc_now(period, counter)
+ }
+
+ fn get_alarm<'a>(&'a self, cs: CriticalSection<'a>, alarm: AlarmHandle) -> &'a AlarmState {
+ // safety: we're allowed to assume the AlarmState is created by us, and
+ // we never create one that's out of bounds.
+ unsafe { self.alarms.borrow(cs).get_unchecked(alarm.id() as usize) }
+ }
+
+ fn trigger_alarm(&self, n: usize, cs: CriticalSection) {
+ let alarm = &self.alarms.borrow(cs)[n];
+ alarm.timestamp.set(u64::MAX);
+
+ // Call after clearing alarm, so the callback can set another alarm.
+
+ // safety:
+ // - we can ignore the possiblity of `f` being unset (null) because of the safety contract of `allocate_alarm`.
+ // - other than that we only store valid function pointers into alarm.callback
+ let f: fn(*mut ()) = unsafe { mem::transmute(alarm.callback.get()) };
+ f(alarm.ctx.get());
+ }
+
+ fn allocate_alarm(&self) -> Option<AlarmHandle> {
+ let id = self
+ .alarm_count
+ .fetch_update(Ordering::AcqRel, Ordering::Acquire, |x| {
+ if x < ALARM_COUNT as u8 {
+ Some(x + 1)
+ } else {
+ None
+ }
+ });
+
+ match id {
+ Ok(id) => Some(unsafe { AlarmHandle::new(id) }),
+ Err(_) => None,
+ }
+ }
+
+ fn set_alarm_callback(&self, alarm: AlarmHandle, callback: fn(*mut ()), ctx: *mut ()) {
+ critical_section::with(|cs| {
+ let alarm = self.get_alarm(cs, alarm);
+
+ // safety: it's OK to transmute a fn pointer into a raw pointer
+ let callback_ptr: *const () = unsafe { mem::transmute(callback) };
+
+ alarm.callback.set(callback_ptr);
+ alarm.ctx.set(ctx);
+ })
+ }
+
+ fn set_alarm(&self, alarm: AlarmHandle, timestamp: u64) {
+ critical_section::with(|cs| {
+ let r = T::regs();
+
+ let n = alarm.id() as _;
+ let alarm = self.get_alarm(cs, alarm);
+ alarm.timestamp.set(timestamp);
+
+ let t = self.now();
+ if timestamp <= t {
+ unsafe { r.dier().modify(|w| w.set_ccie(n + 1, false)) };
+ self.trigger_alarm(n, cs);
+ return;
+ }
+
+ let safe_timestamp = timestamp.max(t + 3);
+
+ // Write the CCR value regardless of whether we're going to enable it now or not.
+ // This way, when we enable it later, the right value is already set.
+ unsafe { r.ccr(n + 1).write(|w| w.set_ccr(safe_timestamp as u16)) };
+
+ // Enable it if it'll happen soon. Otherwise, `next_period` will enable it.
+ let diff = timestamp - t;
+ // NOTE(unsafe) We're in a critical section
+ unsafe { r.dier().modify(|w| w.set_ccie(n + 1, diff < 0xc000)) };
+ })
+ }
+}
+
+struct RtcDriver;
+embassy::time_driver_impl!(RtcDriver);
+
+impl Driver for RtcDriver {
+ fn now() -> u64 {
+ STATE.now()
+ }
+
+ unsafe fn allocate_alarm() -> Option<AlarmHandle> {
+ STATE.allocate_alarm()
+ }
+
+ fn set_alarm_callback(alarm: AlarmHandle, callback: fn(*mut ()), ctx: *mut ()) {
+ STATE.set_alarm_callback(alarm, callback, ctx)
+ }
+
+ fn set_alarm(alarm: AlarmHandle, timestamp: u64) {
+ STATE.set_alarm(alarm, timestamp)
+ }
+}
+
+#[interrupt]
+fn TIM3() {
+ STATE.on_interrupt()
+}
+
+pub(crate) fn init() {
+ STATE.init()
+}
+
+// ------------------------------------------------------
+
+pub(crate) mod sealed {
+ use super::*;
+ pub trait Instance {
+ type Interrupt: Interrupt;
+
+ fn regs() -> TimGp16;
+ }
+}
+
+pub trait Instance: sealed::Instance + Sized + RccPeripheral + 'static {}
+
+macro_rules! impl_timer {
+ ($inst:ident) => {
+ impl sealed::Instance for peripherals::$inst {
+ type Interrupt = crate::interrupt::$inst;
+
+ fn regs() -> TimGp16 {
+ crate::pac::$inst
+ }
+ }
+
+ impl Instance for peripherals::$inst {}
+ };
+}
+
+crate::pac::peripherals!(
+ (timer, TIM2) => { impl_timer!(TIM2); };
+ (timer, TIM3) => { impl_timer!(TIM3); };
+ (timer, TIM4) => { impl_timer!(TIM4); };
+ (timer, TIM5) => { impl_timer!(TIM5); };
+);
diff --git a/embassy/src/executor/mod.rs b/embassy/src/executor/mod.rs
index 771f75ee..ee05b676 100644
--- a/embassy/src/executor/mod.rs
+++ b/embassy/src/executor/mod.rs
@@ -109,18 +109,13 @@ pub struct Executor {
}
impl Executor {
- pub const fn new() -> Self {
+ pub fn new() -> Self {
Self {
inner: raw::Executor::new(|_| cortex_m::asm::sev(), ptr::null_mut()),
not_send: PhantomData,
}
}
- #[cfg(feature = "time")]
- pub fn set_alarm(&mut self, alarm: &'static dyn crate::time::Alarm) {
- self.inner.set_alarm(alarm);
- }
-
/// Runs the executor.
///
/// This function never returns.
@@ -161,11 +156,6 @@ impl<I: Interrupt> InterruptExecutor<I> {
}
}
- #[cfg(feature = "time")]
- pub fn set_alarm(&mut self, alarm: &'static dyn crate::time::Alarm) {
- self.inner.set_alarm(alarm);
- }
-
/// Start the executor.
///
/// `init` is called in the interrupt context, then the interrupt is
diff --git a/embassy/src/executor/raw.rs b/embassy/src/executor/raw.rs
index cd2f0446..fac46d1f 100644
--- a/embassy/src/executor/raw.rs
+++ b/embassy/src/executor/raw.rs
@@ -15,7 +15,9 @@ use super::SpawnToken;
#[cfg(feature = "time")]
use super::timer_queue::{TimerQueue, TimerQueueItem};
#[cfg(feature = "time")]
-use crate::time::{Alarm, Instant};
+use crate::time::driver::{self, AlarmHandle};
+#[cfg(feature = "time")]
+use crate::time::Instant;
/// Task is spawned (has a future)
pub(crate) const STATE_SPAWNED: u32 = 1 << 0;
@@ -169,11 +171,16 @@ pub struct Executor {
#[cfg(feature = "time")]
timer_queue: TimerQueue,
#[cfg(feature = "time")]
- alarm: Option<&'static dyn Alarm>,
+ alarm: AlarmHandle,
}
impl Executor {
- pub const fn new(signal_fn: fn(*mut ()), signal_ctx: *mut ()) -> Self {
+ pub fn new(signal_fn: fn(*mut ()), signal_ctx: *mut ()) -> Self {
+ #[cfg(feature = "time")]
+ let alarm = unsafe { unwrap!(driver::allocate_alarm()) };
+ #[cfg(feature = "time")]
+ driver::set_alarm_callback(alarm, signal_fn, signal_ctx);
+
Self {
run_queue: RunQueue::new(),
signal_fn,
@@ -182,15 +189,10 @@ impl Executor {
#[cfg(feature = "time")]
timer_queue: TimerQueue::new(),
#[cfg(feature = "time")]
- alarm: None,
+ alarm,
}
}
- #[cfg(feature = "time")]
- pub fn set_alarm(&mut self, alarm: &'static dyn Alarm) {
- self.alarm = Some(alarm);
- }
-
pub fn set_signal_ctx(&mut self, signal_ctx: *mut ()) {
self.signal_ctx = signal_ctx;
}
@@ -209,11 +211,9 @@ impl Executor {
pub unsafe fn run_queued(&'static self) {
#[cfg(feature = "time")]
- if self.alarm.is_some() {
- self.timer_queue.dequeue_expired(Instant::now(), |p| {
- p.as_ref().enqueue();
- });
- }
+ self.timer_queue.dequeue_expired(Instant::now(), |p| {
+ p.as_ref().enqueue();
+ });
self.run_queue.dequeue_all(|p| {
let task = p.as_ref();
@@ -239,13 +239,12 @@ impl Executor {
self.timer_queue.update(p);
});
- // If this is in the past, set_alarm will immediately trigger the alarm,
- // which will make the wfe immediately return so we do another loop iteration.
#[cfg(feature = "time")]
- if let Some(alarm) = self.alarm {
+ {
+ // If this is in the past, set_alarm will immediately trigger the alarm,
+ // which will make the wfe immediately return so we do another loop iteration.
let next_expiration = self.timer_queue.next_expiration();
- alarm.set_callback(self.signal_fn, self.signal_ctx);
- alarm.set(next_expiration.as_ticks());
+ driver::set_alarm(self.alarm, next_expiration.as_ticks());
}
}
diff --git a/embassy/src/time/driver.rs b/embassy/src/time/driver.rs
new file mode 100644
index 00000000..b09cffd8
--- /dev/null
+++ b/embassy/src/time/driver.rs
@@ -0,0 +1,118 @@
+/// Alarm handle, assigned by the driver.
+#[derive(Clone, Copy)]
+pub struct AlarmHandle {
+ id: u8,
+}
+
+impl AlarmHandle {
+ /// Create an AlarmHandle
+ ///
+ /// Safety: May only be called by the current global Driver impl.
+ /// The impl is allowed to rely on the fact that all `AlarmHandle` instances
+ /// are created by itself in unsafe code (e.g. indexing operations)
+ pub unsafe fn new(id: u8) -> Self {
+ Self { id }
+ }
+
+ /// Get the ID of the AlarmHandle.
+ pub fn id(&self) -> u8 {
+ self.id
+ }
+}
+
+/// Time driver
+pub trait Driver {
+ /// 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.
+ fn now() -> u64;
+
+ /// Try allocating an alarm handle. Returns None if no alarms left.
+ /// Initially the alarm has no callback set, and a null `ctx` pointer.
+ ///
+ /// # Safety
+ /// It is UB to make the alarm fire before setting a callback.
+ unsafe fn allocate_alarm() -> Option<AlarmHandle>;
+
+ /// Sets the callback function to be called when the alarm triggers.
+ /// The callback may be called from any context (interrupt or thread mode).
+ fn set_alarm_callback(alarm: AlarmHandle, callback: fn(*mut ()), ctx: *mut ());
+
+ /// Sets an alarm at the given timestamp. When the current timestamp reaches that
+ /// timestamp, the provided callback funcion will be called.
+ ///
+ /// When callback is called, it is guaranteed that now() will return a value greater or equal than timestamp.
+ ///
+ /// Only one alarm can be active at a time. This overwrites any previously-set alarm if any.
+ fn set_alarm(alarm: AlarmHandle, timestamp: u64);
+}
+
+extern "Rust" {
+ fn _embassy_time_now() -> u64;
+ fn _embassy_time_allocate_alarm() -> Option<AlarmHandle>;
+ fn _embassy_time_set_alarm_callback(alarm: AlarmHandle, callback: fn(*mut ()), ctx: *mut ());
+ fn _embassy_time_set_alarm(alarm: AlarmHandle, timestamp: u64);
+}
+
+pub(crate) fn now() -> u64 {
+ unsafe { _embassy_time_now() }
+}
+/// Safety: it is UB to make the alarm fire before setting a callback.
+pub(crate) unsafe fn allocate_alarm() -> Option<AlarmHandle> {
+ _embassy_time_allocate_alarm()
+}
+pub(crate) fn set_alarm_callback(alarm: AlarmHandle, callback: fn(*mut ()), ctx: *mut ()) {
+ unsafe { _embassy_time_set_alarm_callback(alarm, callback, ctx) }
+}
+pub(crate) fn set_alarm(alarm: AlarmHandle, timestamp: u64) {
+ unsafe { _embassy_time_set_alarm(alarm, timestamp) }
+}
+
+/// Set the time Driver implementation.
+///
+/// # Example
+///
+/// ```
+/// struct MyDriver;
+/// embassy::time_driver_impl!(MyDriver);
+///
+/// unsafe impl embassy::time::driver::Driver for MyDriver {
+/// fn now() -> u64 {
+/// todo!()
+/// }
+/// unsafe fn allocate_alarm() -> Option<AlarmHandle> {
+/// todo!()
+/// }
+/// fn set_alarm_callback(alarm: AlarmHandle, callback: fn(*mut ()), ctx: *mut ()) {
+/// todo!()
+/// }
+/// fn set_alarm(alarm: AlarmHandle, timestamp: u64) {
+/// todo!()
+/// }
+/// }
+///
+#[macro_export]
+macro_rules! time_driver_impl {
+ ($t: ty) => {
+ #[no_mangle]
+ fn _embassy_time_now() -> u64 {
+ <$t as $crate::time::driver::Driver>::now()
+ }
+ #[no_mangle]
+ unsafe fn _embassy_time_allocate_alarm() -> Option<AlarmHandle> {
+ <$t as $crate::time::driver::Driver>::allocate_alarm()
+ }
+ #[no_mangle]
+ fn _embassy_time_set_alarm_callback(
+ alarm: AlarmHandle,
+ callback: fn(*mut ()),
+ ctx: *mut (),
+ ) {
+ <$t as $crate::time::driver::Driver>::set_alarm_callback(alarm, callback, ctx)
+ }
+ #[no_mangle]
+ fn _embassy_time_set_alarm(alarm: AlarmHandle, timestamp: u64) {
+ <$t as $crate::time::driver::Driver>::set_alarm(alarm, timestamp)
+ }
+ };
+}
diff --git a/embassy/src/time/instant.rs b/embassy/src/time/instant.rs
index 61a61def..3d430d88 100644
--- a/embassy/src/time/instant.rs
+++ b/embassy/src/time/instant.rs
@@ -1,8 +1,7 @@
use core::fmt;
use core::ops::{Add, AddAssign, Sub, SubAssign};
-use super::TICKS_PER_SECOND;
-use super::{now, Duration};
+use super::{driver, Duration, TICKS_PER_SECOND};
#[derive(Debug, Copy, Clone, PartialEq, Eq, PartialOrd, Ord)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
@@ -17,7 +16,9 @@ impl Instant {
/// Returns an Instant representing the current time.
pub fn now() -> Instant {
- Instant { ticks: now() }
+ Instant {
+ ticks: driver::now(),
+ }
}
/// Instant as clock ticks since MCU start.
diff --git a/embassy/src/time/mod.rs b/embassy/src/time/mod.rs
index d9777c45..f5ad1b3f 100644
--- a/embassy/src/time/mod.rs
+++ b/embassy/src/time/mod.rs
@@ -1,17 +1,15 @@
//! Time abstractions
-//! To use these abstractions, first call `set_clock` with an instance of an [Clock](trait.Clock.html).
-//!
+
mod delay;
+pub mod driver;
mod duration;
mod instant;
mod timer;
-mod traits;
pub use delay::{block_for, Delay};
pub use duration::Duration;
pub use instant::Instant;
pub use timer::{with_timeout, Ticker, TimeoutError, Timer};
-pub use traits::*;
#[cfg(feature = "time-tick-1000hz")]
pub const TICKS_PER_SECOND: u64 = 1_000;
@@ -21,19 +19,3 @@ pub const TICKS_PER_SECOND: u64 = 32_768;
#[cfg(feature = "time-tick-1mhz")]
pub const TICKS_PER_SECOND: u64 = 1_000_000;
-
-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() }
-}
diff --git a/embassy/src/time/traits.rs b/embassy/src/time/traits.rs
deleted file mode 100644
index 4c6134c3..00000000
--- a/embassy/src/time/traits.rs
+++ /dev/null
@@ -1,32 +0,0 @@
-/// Monotonic clock
-pub trait 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.
- fn now(&self) -> u64;
-}
-
-impl<T: Clock + ?Sized> Clock for &T {
- fn now(&self) -> u64 {
- T::now(self)
- }
-}
-
-/// Trait to register a callback at a given timestamp.
-pub trait Alarm {
- /// Sets the callback function to be called when the alarm triggers.
- /// The callback may be called from any context (interrupt or thread mode).
- fn set_callback(&self, callback: fn(*mut ()), ctx: *mut ());
-
- /// Sets an alarm at the given timestamp. When the clock reaches that
- /// timestamp, the provided callback funcion will be called.
- ///
- /// When callback is called, it is guaranteed that now() will return a value greater or equal than timestamp.
- ///
- /// Only one alarm can be active at a time. This overwrites any previously-set alarm if any.
- fn set(&self, timestamp: u64);
-
- /// Clears the previously-set alarm.
- /// If no alarm was set, this is a noop.
- fn clear(&self);
-}
diff --git a/examples/nrf/src/bin/blinky.rs b/examples/nrf/src/bin/blinky.rs
index 77b08b09..6d4561be 100644
--- a/examples/nrf/src/bin/blinky.rs
+++ b/examples/nrf/src/bin/blinky.rs
@@ -6,7 +6,6 @@
#[path = "../example_common.rs"]
mod example_common;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy::time::{Duration, Timer};
use embassy_nrf::gpio::{Level, Output, OutputDrive};
diff --git a/examples/nrf/src/bin/executor_fairness_test.rs b/examples/nrf/src/bin/executor_fairness_test.rs
index d874013f..2d81a755 100644
--- a/examples/nrf/src/bin/executor_fairness_test.rs
+++ b/examples/nrf/src/bin/executor_fairness_test.rs
@@ -8,10 +8,9 @@ mod example_common;
use example_common::*;
use core::task::Poll;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy::time::{Duration, Instant, Timer};
-use embassy_nrf::{interrupt, Peripherals};
+use embassy_nrf::Peripherals;
#[embassy::task]
async fn run1() {
diff --git a/examples/nrf/src/bin/gpiote_channel.rs b/examples/nrf/src/bin/gpiote_channel.rs
index a132f846..a96523e6 100644
--- a/examples/nrf/src/bin/gpiote_channel.rs
+++ b/examples/nrf/src/bin/gpiote_channel.rs
@@ -7,11 +7,10 @@
mod example_common;
use example_common::*;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy_nrf::gpio::{Input, Pull};
use embassy_nrf::gpiote::{InputChannel, InputChannelPolarity};
-use embassy_nrf::{interrupt, Peripherals};
+use embassy_nrf::Peripherals;
#[embassy::main]
async fn main(_spawner: Spawner, p: Peripherals) {
diff --git a/examples/nrf/src/bin/gpiote_port.rs b/examples/nrf/src/bin/gpiote_port.rs
index a782d893..700247d3 100644
--- a/examples/nrf/src/bin/gpiote_port.rs
+++ b/examples/nrf/src/bin/gpiote_port.rs
@@ -6,12 +6,10 @@
#[path = "../example_common.rs"]
mod example_common;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy::traits::gpio::{WaitForHigh, WaitForLow};
use embassy_nrf::gpio::{AnyPin, Input, Pin as _, Pull};
use embassy_nrf::gpiote::PortInput;
-use embassy_nrf::interrupt;
use embassy_nrf::Peripherals;
use example_common::*;
diff --git a/examples/nrf/src/bin/mpsc.rs b/examples/nrf/src/bin/mpsc.rs
index c4c0572b..e31754eb 100644
--- a/examples/nrf/src/bin/mpsc.rs
+++ b/examples/nrf/src/bin/mpsc.rs
@@ -6,7 +6,6 @@
#[path = "../example_common.rs"]
mod example_common;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy::time::{Duration, Timer};
use embassy::util::mpsc::TryRecvError;
diff --git a/examples/nrf/src/bin/multiprio.rs b/examples/nrf/src/bin/multiprio.rs
index 7ce79168..b91bbb74 100644
--- a/examples/nrf/src/bin/multiprio.rs
+++ b/examples/nrf/src/bin/multiprio.rs
@@ -68,7 +68,7 @@ use embassy::executor::{Executor, InterruptExecutor};
use embassy::interrupt::InterruptExt;
use embassy::time::{Duration, Instant, Timer};
use embassy::util::Forever;
-use embassy_nrf::{interrupt, peripherals, rtc};
+use embassy_nrf::interrupt;
#[embassy::task]
async fn run_high() {
@@ -112,30 +112,20 @@ async fn run_low() {
}
}
-static RTC: Forever<rtc::RTC<peripherals::RTC1>> = Forever::new();
-static ALARM_HIGH: Forever<rtc::Alarm<peripherals::RTC1>> = Forever::new();
static EXECUTOR_HIGH: Forever<InterruptExecutor<interrupt::SWI1_EGU1>> = Forever::new();
-static ALARM_MED: Forever<rtc::Alarm<peripherals::RTC1>> = Forever::new();
static EXECUTOR_MED: Forever<InterruptExecutor<interrupt::SWI0_EGU0>> = Forever::new();
-static ALARM_LOW: Forever<rtc::Alarm<peripherals::RTC1>> = Forever::new();
static EXECUTOR_LOW: Forever<Executor> = Forever::new();
#[entry]
fn main() -> ! {
info!("Hello World!");
- let p = embassy_nrf::init(Default::default());
-
- let rtc = RTC.put(rtc::RTC::new(p.RTC1, interrupt::take!(RTC1)));
- rtc.start();
- unsafe { embassy::time::set_clock(rtc) };
+ let _p = embassy_nrf::init(Default::default());
// High-priority executor: SWI1_EGU1, priority level 6
let irq = interrupt::take!(SWI1_EGU1);
irq.set_priority(interrupt::Priority::P6);
- let alarm = ALARM_HIGH.put(rtc.alarm2());
let executor = EXECUTOR_HIGH.put(InterruptExecutor::new(irq));
- executor.set_alarm(alarm);
executor.start(|spawner| {
unwrap!(spawner.spawn(run_high()));
});
@@ -143,17 +133,13 @@ fn main() -> ! {
// Medium-priority executor: SWI0_EGU0, priority level 7
let irq = interrupt::take!(SWI0_EGU0);
irq.set_priority(interrupt::Priority::P7);
- let alarm = ALARM_MED.put(rtc.alarm1());
let executor = EXECUTOR_MED.put(InterruptExecutor::new(irq));
- executor.set_alarm(alarm);
executor.start(|spawner| {
unwrap!(spawner.spawn(run_med()));
});
// Low priority executor: runs in thread mode, using WFE/SEV
- let alarm = ALARM_LOW.put(rtc.alarm0());
let executor = EXECUTOR_LOW.put(Executor::new());
- executor.set_alarm(alarm);
executor.run(|spawner| {
unwrap!(spawner.spawn(run_low()));
});
diff --git a/examples/nrf/src/bin/ppi.rs b/examples/nrf/src/bin/ppi.rs
index 0bac875b..2dc3fe1b 100644
--- a/examples/nrf/src/bin/ppi.rs
+++ b/examples/nrf/src/bin/ppi.rs
@@ -8,12 +8,11 @@ mod example_common;
use example_common::*;
use core::future::pending;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy_nrf::gpio::{Input, Level, Output, OutputDrive, Pull};
use embassy_nrf::gpiote::{self, InputChannel, InputChannelPolarity};
use embassy_nrf::ppi::Ppi;
-use embassy_nrf::{interrupt, Peripherals};
+use embassy_nrf::Peripherals;
use gpiote::{OutputChannel, OutputChannelPolarity};
#[embassy::main]
diff --git a/examples/nrf/src/bin/pwm.rs b/examples/nrf/src/bin/pwm.rs
index d2bc81ce..f30ad8f5 100644
--- a/examples/nrf/src/bin/pwm.rs
+++ b/examples/nrf/src/bin/pwm.rs
@@ -5,11 +5,11 @@
#[path = "../example_common.rs"]
mod example_common;
-use defmt::{panic, *};
+use defmt::*;
use embassy::executor::Spawner;
use embassy::time::{Duration, Timer};
use embassy_nrf::pwm::{Prescaler, Pwm};
-use embassy_nrf::{interrupt, Peripherals};
+use embassy_nrf::Peripherals;
// for i in range(1024): print(int((math.sin(i/512*math.pi)*0.4+0.5)**2*32767), ', ', end='')
static DUTY: [u16; 1024] = [
diff --git a/examples/nrf/src/bin/raw_spawn.rs b/examples/nrf/src/bin/raw_spawn.rs
index 78de7b10..326dd9aa 100644
--- a/examples/nrf/src/bin/raw_spawn.rs
+++ b/examples/nrf/src/bin/raw_spawn.rs
@@ -7,13 +7,11 @@ use example_common::*;
use core::mem;
use cortex_m_rt::entry;
-use defmt::panic;
+
use embassy::executor::raw::Task;
use embassy::executor::Executor;
use embassy::time::{Duration, Timer};
use embassy::util::Forever;
-use embassy_nrf::peripherals;
-use embassy_nrf::{interrupt, rtc};
async fn run1() {
loop {
@@ -29,23 +27,14 @@ async fn run2() {
}
}
-static RTC: Forever<rtc::RTC<peripherals::RTC1>> = Forever::new();
-static ALARM: Forever<rtc::Alarm<peripherals::RTC1>> = Forever::new();
static EXECUTOR: Forever<Executor> = Forever::new();
#[entry]
fn main() -> ! {
info!("Hello World!");
- let p = embassy_nrf::init(Default::default());
-
- let rtc = RTC.put(rtc::RTC::new(p.RTC1, interrupt::take!(RTC1)));
- rtc.start();
- unsafe { embassy::time::set_clock(rtc) };
-
- let alarm = ALARM.put(rtc.alarm0());
+ let _p = embassy_nrf::init(Default::default());
let executor = EXECUTOR.put(Executor::new());
- executor.set_alarm(alarm);
let run1_task = Task::new();
let run2_task = Task::new();
diff --git a/examples/nrf/src/bin/timer.rs b/examples/nrf/src/bin/timer.rs
index 630ea87a..60cbe5a0 100644
--- a/examples/nrf/src/bin/timer.rs
+++ b/examples/nrf/src/bin/timer.rs
@@ -8,7 +8,6 @@ mod example_common;
use embassy_nrf::Peripherals;
use example_common::*;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy::time::{Duration, Timer};
diff --git a/examples/stm32f4/src/bin/blinky.rs b/examples/stm32f4/src/bin/blinky.rs
index 9c695a80..00eab761 100644
--- a/examples/stm32f4/src/bin/blinky.rs
+++ b/examples/stm32f4/src/bin/blinky.rs
@@ -6,7 +6,6 @@
#[path = "../example_common.rs"]
mod example_common;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy::time::{Duration, Timer};
use embassy_stm32::dbgmcu::Dbgmcu;
diff --git a/examples/stm32f4/src/bin/button_exti.rs b/examples/stm32f4/src/bin/button_exti.rs
index caebdac1..ee43fa7d 100644
--- a/examples/stm32f4/src/bin/button_exti.rs
+++ b/examples/stm32f4/src/bin/button_exti.rs
@@ -6,7 +6,6 @@
#[path = "../example_common.rs"]
mod example_common;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy_stm32::dbgmcu::Dbgmcu;
use embassy_stm32::exti::ExtiInput;
diff --git a/examples/stm32f4/src/bin/hello.rs b/examples/stm32f4/src/bin/hello.rs
index 41d80840..1b8730ae 100644
--- a/examples/stm32f4/src/bin/hello.rs
+++ b/examples/stm32f4/src/bin/hello.rs
@@ -4,7 +4,7 @@
#![feature(type_alias_impl_trait)]
#![allow(incomplete_features)]
-use defmt::{info, panic};
+use defmt::info;
use embassy::executor::Spawner;
use embassy::time::{Duration, Timer};
use embassy_stm32::time::Hertz;
diff --git a/examples/stm32f4/src/bin/spi_dma.rs b/examples/stm32f4/src/bin/spi_dma.rs
index 9f710112..a965bef7 100644
--- a/examples/stm32f4/src/bin/spi_dma.rs
+++ b/examples/stm32f4/src/bin/spi_dma.rs
@@ -8,7 +8,6 @@
mod example_common;
use core::fmt::Write;
use core::str::from_utf8;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy_stm32::dbgmcu::Dbgmcu;
use embassy_stm32::spi::{Config, Spi};
diff --git a/examples/stm32f4/src/bin/usart_dma.rs b/examples/stm32f4/src/bin/usart_dma.rs
index 5023075f..05a550e9 100644
--- a/examples/stm32f4/src/bin/usart_dma.rs
+++ b/examples/stm32f4/src/bin/usart_dma.rs
@@ -7,7 +7,6 @@
#[path = "../example_common.rs"]
mod example_common;
use core::fmt::Write;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy_stm32::dbgmcu::Dbgmcu;
use embassy_stm32::dma::NoDma;
diff --git a/examples/stm32h7/src/bin/blinky.rs b/examples/stm32h7/src/bin/blinky.rs
index 3291f5e8..b5e0c18a 100644
--- a/examples/stm32h7/src/bin/blinky.rs
+++ b/examples/stm32h7/src/bin/blinky.rs
@@ -6,30 +6,29 @@
#[path = "../example_common.rs"]
mod example_common;
+use embassy::executor::Spawner;
+use embassy::time::{Duration, Timer};
+use embassy_stm32::dbgmcu::Dbgmcu;
use embassy_stm32::gpio::{Level, Output, Speed};
+use embassy_stm32::Peripherals;
use embedded_hal::digital::v2::OutputPin;
use example_common::*;
-use cortex_m_rt::entry;
-use embassy_stm32::dbgmcu::Dbgmcu;
-
-#[entry]
-fn main() -> ! {
+#[embassy::main]
+async fn main(_spawner: Spawner, p: Peripherals) {
info!("Hello World!");
unsafe { Dbgmcu::enable_all() };
- let p = embassy_stm32::init(Default::default());
-
let mut led = Output::new(p.PB14, Level::High, Speed::Low);
loop {
info!("high");
led.set_high().unwrap();
- cortex_m::asm::delay(10_000_000);
+ Timer::after(Duration::from_millis(500)).await;
info!("low");
led.set_low().unwrap();
- cortex_m::asm::delay(10_000_000);
+ Timer::after(Duration::from_millis(500)).await;
}
}
diff --git a/examples/stm32h7/src/bin/eth.rs b/examples/stm32h7/src/bin/eth.rs
index 6c4ba6eb..e8d13876 100644
--- a/examples/stm32h7/src/bin/eth.rs
+++ b/examples/stm32h7/src/bin/eth.rs
@@ -19,7 +19,6 @@ use embassy_macros::interrupt_take;
use embassy_net::{
Config as NetConfig, Ipv4Address, Ipv4Cidr, StackResources, StaticConfigurator, TcpSocket,
};
-use embassy_stm32::clock::{Alarm, Clock};
use embassy_stm32::dbgmcu::Dbgmcu;
use embassy_stm32::eth::lan8742a::LAN8742A;
use embassy_stm32::eth::{Ethernet, State};
@@ -27,7 +26,7 @@ use embassy_stm32::rng::Random;
use embassy_stm32::{interrupt, peripherals};
use heapless::Vec;
use panic_probe as _;
-use peripherals::{RNG, TIM2};
+use peripherals::RNG;
#[embassy::task]
async fn main_task(
@@ -86,8 +85,6 @@ fn _embassy_rand(buf: &mut [u8]) {
static mut RNG_INST: Option<Random<RNG>> = None;
static EXECUTOR: Forever<Executor> = Forever::new();
-static TIMER_RTC: Forever<Clock<TIM2>> = Forever::new();
-static ALARM: Forever<Alarm<TIM2>> = Forever::new();
static STATE: Forever<State<'static, 4, 4>> = Forever::new();
static ETH: Forever<Ethernet<'static, LAN8742A, 4, 4>> = Forever::new();
static CONFIG: Forever<StaticConfigurator> = Forever::new();
@@ -105,13 +102,6 @@ fn main() -> ! {
let p = embassy_stm32::init(config());
- let rtc_int = interrupt_take!(TIM2);
- let rtc = TIMER_RTC.put(Clock::new(p.TIM2, rtc_int));
- rtc.start();
- let alarm = ALARM.put(rtc.alarm1());
-
- unsafe { embassy::time::set_clock(rtc) };
-
let rng = Random::new(p.RNG);
unsafe {
RNG_INST.replace(rng);
@@ -136,7 +126,6 @@ fn main() -> ! {
let config = CONFIG.put(config);
let executor = EXECUTOR.put(Executor::new());
- executor.set_alarm(alarm);
executor.run(move |spawner| {
unwrap!(spawner.spawn(main_task(eth, config, spawner)));
diff --git a/examples/stm32h7/src/bin/spi.rs b/examples/stm32h7/src/bin/spi.rs
index 5175538d..047b6584 100644
--- a/examples/stm32h7/src/bin/spi.rs
+++ b/examples/stm32h7/src/bin/spi.rs
@@ -9,7 +9,6 @@ mod example_common;
use core::fmt::Write;
use embassy::executor::Executor;
-use embassy::time::Clock;
use embassy::util::Forever;
use embassy_stm32::dma::NoDma;
use embassy_stm32::spi;
@@ -38,14 +37,6 @@ async fn main_task(mut spi: spi::Spi<'static, SPI3, NoDma, NoDma>) {
}
}
-struct ZeroClock;
-
-impl Clock for ZeroClock {
- fn now(&self) -> u64 {
- 0
- }
-}
-
static EXECUTOR: Forever<Executor> = Forever::new();
#[entry]
@@ -69,7 +60,6 @@ fn main() -> ! {
spi::Config::default(),
);
- unsafe { embassy::time::set_clock(&ZeroClock) };
let executor = EXECUTOR.put(Executor::new());
executor.run(|spawner| {
diff --git a/examples/stm32h7/src/bin/spi_dma.rs b/examples/stm32h7/src/bin/spi_dma.rs
index 3b9043bc..f11b7eb4 100644
--- a/examples/stm32h7/src/bin/spi_dma.rs
+++ b/examples/stm32h7/src/bin/spi_dma.rs
@@ -9,7 +9,6 @@ mod example_common;
use core::fmt::Write;
use embassy::executor::Executor;
-use embassy::time::Clock;
use embassy::util::Forever;
use embassy_stm32::time::U32Ext;
use embassy_traits::spi::FullDuplex;
@@ -34,14 +33,6 @@ async fn main_task(mut spi: spi::Spi<'static, SPI3, DMA1_CH3, DMA1_CH4>) {
}
}
-struct ZeroClock;
-
-impl Clock for ZeroClock {
- fn now(&self) -> u64 {
- 0
- }
-}
-
static EXECUTOR: Forever<Executor> = Forever::new();
#[entry]
@@ -65,7 +56,6 @@ fn main() -> ! {
spi::Config::default(),
);
- unsafe { embassy::time::set_clock(&ZeroClock) };
let executor = EXECUTOR.put(Executor::new());
executor.run(|spawner| {
diff --git a/examples/stm32h7/src/bin/usart.rs b/examples/stm32h7/src/bin/usart.rs
index 5fa21b6a..9c93d3f2 100644
--- a/examples/stm32h7/src/bin/usart.rs
+++ b/examples/stm32h7/src/bin/usart.rs
@@ -8,7 +8,6 @@
mod example_common;
use cortex_m::prelude::_embedded_hal_blocking_serial_Write;
use embassy::executor::Executor;
-use embassy::time::Clock;
use embassy::util::Forever;
use embassy_stm32::dma::NoDma;
use embassy_stm32::usart::{Config, Uart};
@@ -34,14 +33,6 @@ async fn main_task() {
}
}
-struct ZeroClock;
-
-impl Clock for ZeroClock {
- fn now(&self) -> u64 {
- 0
- }
-}
-
static EXECUTOR: Forever<Executor> = Forever::new();
#[entry]
@@ -52,8 +43,6 @@ fn main() -> ! {
Dbgmcu::enable_all();
}
- unsafe { embassy::time::set_clock(&ZeroClock) };
-
let executor = EXECUTOR.put(Executor::new());
executor.run(|spawner| {
diff --git a/examples/stm32h7/src/bin/usart_dma.rs b/examples/stm32h7/src/bin/usart_dma.rs
index 26cc3c5d..3f70a82b 100644
--- a/examples/stm32h7/src/bin/usart_dma.rs
+++ b/examples/stm32h7/src/bin/usart_dma.rs
@@ -8,7 +8,6 @@
mod example_common;
use core::fmt::Write;
use embassy::executor::Executor;
-use embassy::time::Clock;
use embassy::util::Forever;
use embassy_stm32::dbgmcu::Dbgmcu;
use embassy_stm32::dma::NoDma;
@@ -36,14 +35,6 @@ async fn main_task() {
}
}
-struct ZeroClock;
-
-impl Clock for ZeroClock {
- fn now(&self) -> u64 {
- 0
- }
-}
-
static EXECUTOR: Forever<Executor> = Forever::new();
#[entry]
@@ -54,8 +45,6 @@ fn main() -> ! {
Dbgmcu::enable_all();
}
- unsafe { embassy::time::set_clock(&ZeroClock) };
-
let executor = EXECUTOR.put(Executor::new());
executor.run(|spawner| {
diff --git a/examples/stm32l0/src/bin/blinky.rs b/examples/stm32l0/src/bin/blinky.rs
index 27060edc..faa42896 100644
--- a/examples/stm32l0/src/bin/blinky.rs
+++ b/examples/stm32l0/src/bin/blinky.rs
@@ -7,7 +7,6 @@
#[path = "../example_common.rs"]
mod example_common;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy::time::{Duration, Timer};
use embassy_stm32::gpio::{Level, Output, Speed};
diff --git a/examples/stm32l0/src/bin/button_exti.rs b/examples/stm32l0/src/bin/button_exti.rs
index 9f0b0bde..40e25b08 100644
--- a/examples/stm32l0/src/bin/button_exti.rs
+++ b/examples/stm32l0/src/bin/button_exti.rs
@@ -7,7 +7,6 @@
#[path = "../example_common.rs"]
mod example_common;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy_stm32::exti::ExtiInput;
use embassy_stm32::gpio::{Input, Pull};
diff --git a/examples/stm32l0/src/bin/usart_dma.rs b/examples/stm32l0/src/bin/usart_dma.rs
index 2c0690d0..39a60517 100644
--- a/examples/stm32l0/src/bin/usart_dma.rs
+++ b/examples/stm32l0/src/bin/usart_dma.rs
@@ -9,7 +9,6 @@ mod example_common;
use example_common::*;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy_stm32::usart::{Config, Uart};
use embassy_stm32::{rcc, Peripherals};
diff --git a/examples/stm32l4/src/bin/blinky.rs b/examples/stm32l4/src/bin/blinky.rs
index c929335d..fc86b11e 100644
--- a/examples/stm32l4/src/bin/blinky.rs
+++ b/examples/stm32l4/src/bin/blinky.rs
@@ -6,7 +6,6 @@
#[path = "../example_common.rs"]
mod example_common;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy::time::{Duration, Timer};
use embassy_stm32::dbgmcu::Dbgmcu;
diff --git a/examples/stm32l4/src/bin/button_exti.rs b/examples/stm32l4/src/bin/button_exti.rs
index a702b5ba..8a78b258 100644
--- a/examples/stm32l4/src/bin/button_exti.rs
+++ b/examples/stm32l4/src/bin/button_exti.rs
@@ -6,7 +6,6 @@
#[path = "../example_common.rs"]
mod example_common;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy_stm32::dbgmcu::Dbgmcu;
use embassy_stm32::exti::ExtiInput;
diff --git a/examples/stm32l4/src/bin/spi_dma.rs b/examples/stm32l4/src/bin/spi_dma.rs
index aa076258..ba77331b 100644
--- a/examples/stm32l4/src/bin/spi_dma.rs
+++ b/examples/stm32l4/src/bin/spi_dma.rs
@@ -7,7 +7,6 @@
#[path = "../example_common.rs"]
mod example_common;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy_stm32::dbgmcu::Dbgmcu;
use embassy_stm32::gpio::{Input, Level, Output, Pull, Speed};
diff --git a/examples/stm32l4/src/bin/usart_dma.rs b/examples/stm32l4/src/bin/usart_dma.rs
index b15bba76..f74a0e06 100644
--- a/examples/stm32l4/src/bin/usart_dma.rs
+++ b/examples/stm32l4/src/bin/usart_dma.rs
@@ -7,7 +7,6 @@
#[path = "../example_common.rs"]
mod example_common;
use core::fmt::Write;
-use defmt::panic;
use embassy::executor::Spawner;
use embassy_stm32::dbgmcu::Dbgmcu;
use embassy_stm32::dma::NoDma;