Embassy enable thread and interrupt by default, enable embassy when building docs (#1485)

* Remove interrupt and thread executor embassy features

* Reserve sw interrupt 3 (4) instead of 0 for multicore systems with the embassy feature enabled

* Remove uneeded #[feature()] from examples

* Fix HIL tests

* Add thread mode context id and fix up examples

* improve embassy module docs

* changelog

* fixup hil tests

* Fixup usb examples
This commit is contained in:
Scott Mabin 2024-05-02 16:58:04 +01:00 committed by GitHub
parent edd03717d2
commit f32565b4af
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
31 changed files with 147 additions and 205 deletions

View File

@ -22,6 +22,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
- i2c: i2c1_handler used I2C0 register block by mistake (#1487) - i2c: i2c1_handler used I2C0 register block by mistake (#1487)
- Removed ESP32 specific code for resolutions > 16 bit in ledc embedded_hal::pwm max_duty_cycle function. (#1441) - Removed ESP32 specific code for resolutions > 16 bit in ledc embedded_hal::pwm max_duty_cycle function. (#1441)
- Fixed division by zero in ledc embedded_hal::pwm set_duty_cycle function and converted to set_duty_hw instead of set_duty to eliminate loss of granularity. (#1441) - Fixed division by zero in ledc embedded_hal::pwm set_duty_cycle function and converted to set_duty_hw instead of set_duty to eliminate loss of granularity. (#1441)
- Embassy examples now build on stable (#1485)
### Changed ### Changed
@ -32,6 +33,9 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
- Make software interrupts shareable (#1500) - Make software interrupts shareable (#1500)
- The `SystemParts` struct has been renamed to `SystemControl`, and now has a constructor which takes the `SYSTEM` peripheral (#1495) - The `SystemParts` struct has been renamed to `SystemControl`, and now has a constructor which takes the `SYSTEM` peripheral (#1495)
- Timer abstraction: refactor `systimer` and `timer` modules into a common `timer` module (#1527) - Timer abstraction: refactor `systimer` and `timer` modules into a common `timer` module (#1527)
- Removed the `embassy-executor-thread` and `embassy-executor-interrupt` features, they are now enabled by default when `embassy` is enabled. (#1485)
- Software interrupt 3 is now used instead of software interrupt 0 on the thread aware executor on multicore systems (#1485)
- Timer abstraction: refactor `systimer` and `timer` modules into a common `timer` module (#1527)
### Removed ### Removed

View File

@ -170,11 +170,7 @@ ufmt = ["dep:ufmt-write"]
#! ### Embassy Feature Flags #! ### Embassy Feature Flags
## Enable support for `embassy`, a modern asynchronous embedded framework. ## Enable support for `embassy`, a modern asynchronous embedded framework.
embassy = ["embassy-time-driver", "procmacros/embassy"] embassy = ["embassy-time-driver", "procmacros/embassy", "embassy-executor"]
## Use the interrupt-mode embassy executor.
embassy-executor-interrupt = ["embassy", "embassy-executor"]
## Use the thread-mode embassy executor.
embassy-executor-thread = ["embassy", "embassy-executor"]
## Uses hardware timers as alarms for the executors. Using this feature ## Uses hardware timers as alarms for the executors. Using this feature
## limits the number of executors to the number of hardware alarms provided ## limits the number of executors to the number of hardware alarms provided
## by the time driver. ## by the time driver.
@ -217,6 +213,8 @@ ci = [
"embedded-hal-02", "embedded-hal-02",
"ufmt", "ufmt",
"async", "async",
"embassy",
"embassy-time-timg0",
] ]
[lints.clippy] [lints.clippy]

View File

@ -1,41 +1,26 @@
#[cfg(feature = "embassy-executor-thread")] mod interrupt;
pub mod thread; mod thread;
#[cfg(feature = "embassy-executor-thread")] pub use interrupt::*;
pub use thread::*; pub use thread::*;
#[cfg(feature = "embassy-executor-interrupt")]
pub mod interrupt;
#[cfg(feature = "embassy-executor-interrupt")]
pub use interrupt::*;
#[cfg(any(
feature = "embassy-executor-thread",
feature = "embassy-executor-interrupt",
))]
#[export_name = "__pender"] #[export_name = "__pender"]
fn __pender(context: *mut ()) { fn __pender(context: *mut ()) {
#[cfg(feature = "embassy-executor-interrupt")]
use crate::system::SoftwareInterrupt; use crate::system::SoftwareInterrupt;
let context = (context as usize).to_le_bytes(); let context = (context as usize).to_le_bytes();
cfg_if::cfg_if! { match context[0] {
if #[cfg(feature = "embassy-executor-interrupt")] { // For interrupt executors, the context value is the
match context[0] { // software interrupt number
#[cfg(feature = "embassy-executor-thread")] 0 => unsafe { SoftwareInterrupt::<0>::steal().raise() },
0 => thread::pend_thread_mode(context[1] as usize), 1 => unsafe { SoftwareInterrupt::<1>::steal().raise() },
2 => unsafe { SoftwareInterrupt::<2>::steal().raise() },
#[cfg(not(feature = "embassy-executor-thread"))] 3 => unsafe { SoftwareInterrupt::<3>::steal().raise() },
0 => unsafe { SoftwareInterrupt::<0>::steal().raise() }, other => {
1 => unsafe { SoftwareInterrupt::<1>::steal().raise() }, assert_eq!(other, THREAD_MODE_CONTEXT);
2 => unsafe { SoftwareInterrupt::<2>::steal().raise() }, // THREAD_MODE_CONTEXT id is reserved for thread mode executors
3 => unsafe { SoftwareInterrupt::<3>::steal().raise() }, thread::pend_thread_mode(context[1] as usize)
_ => {}
}
} else {
pend_thread_mode(context[1] as usize);
} }
} }
} }

View File

@ -10,6 +10,8 @@ use crate::get_core;
#[cfg(multi_core)] #[cfg(multi_core)]
use crate::peripherals::SYSTEM; use crate::peripherals::SYSTEM;
pub(crate) const THREAD_MODE_CONTEXT: u8 = 16;
/// global atomic used to keep track of whether there is work to do since sev() /// global atomic used to keep track of whether there is work to do since sev()
/// is not available on either Xtensa or RISC-V /// is not available on either Xtensa or RISC-V
#[cfg(not(multi_core))] #[cfg(not(multi_core))]
@ -19,15 +21,15 @@ static SIGNAL_WORK_THREAD_MODE: [AtomicBool; 2] = [AtomicBool::new(false), Atomi
#[cfg(multi_core)] #[cfg(multi_core)]
#[handler] #[handler]
fn software0_interrupt() { fn software3_interrupt() {
// This interrupt is fired when the thread-mode executor's core needs to be // This interrupt is fired when the thread-mode executor's core needs to be
// woken. It doesn't matter which core handles this interrupt first, the // woken. It doesn't matter which core handles this interrupt first, the
// point is just to wake up the core that is currently executing // point is just to wake up the core that is currently executing
// `waiti`. // `waiti`.
let system = unsafe { &*SYSTEM::PTR }; let system = unsafe { &*SYSTEM::PTR };
system system
.cpu_intr_from_cpu_0() .cpu_intr_from_cpu_3()
.write(|w| w.cpu_intr_from_cpu_0().bit(false)); .write(|w| w.cpu_intr_from_cpu_3().bit(false));
} }
pub(crate) fn pend_thread_mode(core: usize) { pub(crate) fn pend_thread_mode(core: usize) {
@ -44,12 +46,21 @@ pub(crate) fn pend_thread_mode(core: usize) {
let system = unsafe { &*SYSTEM::PTR }; let system = unsafe { &*SYSTEM::PTR };
system system
.cpu_intr_from_cpu_0() .cpu_intr_from_cpu_3()
.write(|w| w.cpu_intr_from_cpu_0().bit(true)); .write(|w| w.cpu_intr_from_cpu_3().bit(true));
} }
} }
/// Multi-core Xtensa Executor /// A thread aware Executor
#[cfg_attr(
multi_core,
doc = r#"
This executor is capable of waking an
executor running on another core if work
needs to be completed there for a task to
progress on this core.
"#
)]
pub struct Executor { pub struct Executor {
inner: raw::Executor, inner: raw::Executor,
not_send: PhantomData<*mut ()>, not_send: PhantomData<*mut ()>,
@ -57,18 +68,27 @@ pub struct Executor {
impl Executor { impl Executor {
/// Create a new Executor. /// Create a new Executor.
/// #[cfg_attr(
/// On multi_core systems this will use software-interrupt 0 which isn't multi_core,
/// available for anything else. doc = r#"
This will use software-interrupt 3 which isn't
available for anything else to wake the other core(s).
"#
)]
pub fn new() -> Self { pub fn new() -> Self {
#[cfg(multi_core)] #[cfg(multi_core)]
unsafe { unsafe {
crate::system::SoftwareInterrupt::<0>::steal() crate::system::SoftwareInterrupt::<3>::steal()
.set_interrupt_handler(software0_interrupt) .set_interrupt_handler(software3_interrupt)
} }
Self { Self {
inner: raw::Executor::new(usize::from_le_bytes([0, get_core() as u8, 0, 0]) as *mut ()), inner: raw::Executor::new(usize::from_le_bytes([
THREAD_MODE_CONTEXT,
get_core() as u8,
0,
0,
]) as *mut ()),
not_send: PhantomData, not_send: PhantomData,
} }
} }

View File

@ -1,81 +1,27 @@
//! # Embassy driver //! # Embassy
//! //!
//! ## Overview //! The [embassy](https://github.com/embassy-rs/embassy) project is a toolkit to leverage async Rust
//! The `embassy` driver for ESP chips is an essential part of the Embassy //! in embedded applications. This module adds the required
//! embedded async/await runtime and is used by applications to perform //! support to use embassy on Espressif chips.
//! time-based operations and schedule asynchronous tasks. It provides a
//! high-level API for handling timers and alarms, abstracting the underlying
//! hardware details, and allowing users to focus on application logic rather
//! than low-level timer management.
//! //!
//! Here are important details about the module: //! ## Initialization
//! * `time_driver` module (`time_driver_systimer` or `time_driver_timg`,
//! depends on enabled feature)
//! - This module contains the implementations of the timer drivers for
//! different ESP chips.<br> It includes the `EmbassyTimer` struct, which
//! is responsible for handling alarms and timer events.
//! - `EmbassyTimer` struct represents timer driver for ESP chips. It
//! contains `alarms` - an array of `AlarmState` structs, which describe
//! the state of alarms associated with the timer driver.
//! * `AlarmState` struct
//! - This struct represents the state of an alarm. It contains information
//! about the alarm's timestamp, a callback function to be executed when
//! the alarm triggers, and a context pointer for passing user-defined
//! data to the callback.
//! * `executor` module
//! - This module contains the implementations of a multi-core safe
//! thread-mode and an interrupt-mode executor for Xtensa-based ESP chips.
//! //!
//! ## Example //! Embassy **must** be initialized by calling [`init`], before beginning any
//! The following example demonstrates how to use the `embassy` driver to //! async operations.
//! schedule asynchronous tasks.<br> In this example, we use the `embassy`
//! driver to wait for a GPIO 9 pin state to change.
//! //!
//! ```no_run //! [`init`] installs a [global time driver](https://github.com/embassy-rs/embassy/tree/main/embassy-time#global-time-driver)
//! #[cfg(feature = "embassy-time-systick")] //! allowing users to use [embassy-time](https://docs.rs/embassy-time/latest/embassy_time/) APIs in any async context
//! embassy::init( //! within their application. A time driver must be chosen by enabling the
//! &clocks, //! correct feature on esp-hal, see the crate level documentation for more
//! esp_hal::systimer::SystemTimer::new(peripherals.SYSTIMER), //! details.
//! );
//! //!
//! #[cfg(feature = "embassy-time-timg0")] //! ## Executors
//! embassy::init(&clocks, timer_group0.timer0);
//! //!
//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! We offer two executor types, a thread mode [`Executor`](executor::Executor)
//! // GPIO 9 as input //! and [`InterruptExecutor`](executor::InterruptExecutor).
//! let input = io.pins.gpio9.into_pull_down_input(); //! An [`InterruptExecutor`](executor::InterruptExecutor) can be used to achieve
//! //! preemptive multitasking in async applications, which is usually something reserved for more traditional RTOS systems, read more about it in [the embassy documentation](https://embassy.dev/book/dev/runtime.html).
//! // Async requires the GPIO interrupt to wake futures
//! esp_hal::interrupt::enable(
//! esp_hal::peripherals::Interrupt::GPIO,
//! esp_hal::interrupt::Priority::Priority1,
//! )
//! .unwrap();
//!
//! let executor = make_static!(Executor::new());
//! executor.run(|spawner| {
//! spawner.spawn(ping(input)).ok();
//! });
//! ```
//!
//! Where `ping` defined as:
//! ```no_run
//! async fn ping(mut pin: Gpio9<Input<PullDown>>) {
//! loop {
//! esp_println::println!("Waiting...");
//! pin.wait_for_rising_edge().await.unwrap();
//! esp_println::println!("Ping!");
//! Timer::after(Duration::from_millis(100)).await;
//! }
//! }
//! ```
//! For more embassy-related examples check out the [examples repo](https://github.com/esp-rs/esp-hal/tree/main/esp32-hal/examples)
//! for a corresponding board.
#[cfg(any(
feature = "embassy-executor-interrupt",
feature = "embassy-executor-thread"
))]
pub mod executor; pub mod executor;
use core::cell::Cell; use core::cell::Cell;
@ -102,12 +48,12 @@ use time_driver::EmbassyTimer;
use crate::clock::Clocks; use crate::clock::Clocks;
/// Initialise embassy /// Initialize embassy
pub fn init(clocks: &Clocks, td: time_driver::TimerType) { pub fn init(clocks: &Clocks, time_driver: time_driver::TimerType) {
EmbassyTimer::init(clocks, td) EmbassyTimer::init(clocks, time_driver)
} }
pub struct AlarmState { pub(crate) struct AlarmState {
pub callback: Cell<Option<(fn(*mut ()), *mut ())>>, pub callback: Cell<Option<(fn(*mut ()), *mut ())>>,
pub allocated: Cell<bool>, pub allocated: Cell<bool>,
} }

View File

@ -229,30 +229,33 @@ impl<const NUM: u8> crate::peripheral::Peripheral for SoftwareInterrupt<NUM> {
impl<const NUM: u8> crate::private::Sealed for SoftwareInterrupt<NUM> {} impl<const NUM: u8> crate::private::Sealed for SoftwareInterrupt<NUM> {}
/// This gives access to the available software interrupts. /// This gives access to the available software interrupts.
/// #[cfg_attr(
/// Please note: Software interrupt 0 is not available when using the multi_core,
/// `embassy-executor-thread` feature doc = r#"
Please note: Software interrupt 3 is reserved
for inter-processor communication when the `embassy`
feature is enabled."#
)]
#[non_exhaustive] #[non_exhaustive]
pub struct SoftwareInterruptControl { pub struct SoftwareInterruptControl {
#[cfg(not(all(feature = "embassy-executor-thread", multi_core)))]
pub software_interrupt0: SoftwareInterrupt<0>, pub software_interrupt0: SoftwareInterrupt<0>,
pub software_interrupt1: SoftwareInterrupt<1>, pub software_interrupt1: SoftwareInterrupt<1>,
pub software_interrupt2: SoftwareInterrupt<2>, pub software_interrupt2: SoftwareInterrupt<2>,
#[cfg(not(all(feature = "embassy", multi_core)))]
pub software_interrupt3: SoftwareInterrupt<3>, pub software_interrupt3: SoftwareInterrupt<3>,
} }
impl SoftwareInterruptControl { impl SoftwareInterruptControl {
fn new() -> Self { fn new() -> Self {
// the thread-executor uses SW-INT0 when used on a multi-core system
// we cannot easily require `software_interrupt0` there since it's created
// before `main` via proc-macro
SoftwareInterruptControl { SoftwareInterruptControl {
#[cfg(not(all(feature = "embassy-executor-thread", multi_core)))] software_interrupt0: SoftwareInterrupt {},
software_interrupt0: SoftwareInterrupt, software_interrupt1: SoftwareInterrupt {},
software_interrupt1: SoftwareInterrupt, software_interrupt2: SoftwareInterrupt {},
software_interrupt2: SoftwareInterrupt, // the thread-executor uses SW-INT3 when used on a multi-core system
software_interrupt3: SoftwareInterrupt, // we cannot easily require `software_interrupt3` there since it's created
// before `main` via proc-macro so we cfg it away from users
#[cfg(not(all(feature = "embassy", multi_core)))]
software_interrupt3: SoftwareInterrupt {},
} }
} }
} }

View File

@ -63,9 +63,6 @@ embedded-hal = ["esp-hal/embedded-hal"]
embassy = ["esp-hal/embassy"] embassy = ["esp-hal/embassy"]
embassy-executor-thread = ["esp-hal/embassy-executor-thread"]
embassy-executor-interrupt = ["esp-hal/embassy-executor-interrupt"]
embassy-time-systick-16mhz = ["esp-hal/embassy-time-systick-16mhz"] embassy-time-systick-16mhz = ["esp-hal/embassy-time-systick-16mhz"]
embassy-time-timg0 = ["esp-hal/embassy-time-timg0"] embassy-time-timg0 = ["esp-hal/embassy-time-timg0"]
embassy-generic-timers = ["embassy-time/generic-queue-8"] embassy-generic-timers = ["embassy-time/generic-queue-8"]

View File

@ -40,7 +40,7 @@ To demonstrated, in `src/bin/embassy_hello_world.rs` you will see the following:
```rust ```rust
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: embassy embassy-generic-timers embassy-time-timg0 embassy-executor-thread //% FEATURES: embassy embassy-generic-timers embassy-time-timg0
``` ```
Another thing to be aware of is the GPIO pins being used. We have tried to use pins available the DevKit-C boards from Espressif, however this is being done on a best-effort basis. Another thing to be aware of is the GPIO pins being used. We have tried to use pins available the DevKit-C boards from Espressif, however this is being done on a best-effort basis.

View File

@ -4,11 +4,10 @@
//! concurrently. //! concurrently.
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: embassy embassy-time-timg0 embassy-executor-thread embassy-generic-timers //% FEATURES: embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_time::{Duration, Timer}; use embassy_time::{Duration, Timer};

View File

@ -6,11 +6,10 @@
//! It's not supported on ESP32, on ESP32-S2 the frequency of the systimer is different (so it's left out here) //! It's not supported on ESP32, on ESP32-S2 the frequency of the systimer is different (so it's left out here)
//% CHIPS: esp32c2 esp32c3 esp32c6 esp32h2 esp32s3 //% CHIPS: esp32c2 esp32c3 esp32c6 esp32h2 esp32s3
//% FEATURES: embassy embassy-time-systick-16mhz embassy-executor-thread embassy-generic-timers //% FEATURES: embassy embassy-time-systick-16mhz embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_time::{Duration, Timer}; use embassy_time::{Duration, Timer};

View File

@ -11,11 +11,10 @@
//! LIS3DH to get accelerometer data. //! LIS3DH to get accelerometer data.
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: async embassy embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: async embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_time::{Duration, Timer}; use embassy_time::{Duration, Timer};

View File

@ -12,7 +12,7 @@
//! //!
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: async embassy embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: async embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]

View File

@ -12,11 +12,10 @@
//! You can also inspect the MCLK, BCLK and WS with a logic analyzer. //! You can also inspect the MCLK, BCLK and WS with a logic analyzer.
//% CHIPS: esp32 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% CHIPS: esp32 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: async embassy embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: async embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner; use embassy_executor::Spawner;
use esp_backtrace as _; use esp_backtrace as _;

View File

@ -27,11 +27,10 @@
//! | XSMT | +3V3 | //! | XSMT | +3V3 |
//% CHIPS: esp32 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% CHIPS: esp32 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: async embassy embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: async embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner; use embassy_executor::Spawner;
use esp_backtrace as _; use esp_backtrace as _;

View File

@ -4,11 +4,10 @@
//! signal set by the task running on the other core. //! signal set by the task running on the other core.
//% CHIPS: esp32 esp32s3 //% CHIPS: esp32 esp32s3
//% FEATURES: embassy embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use core::ptr::addr_of_mut; use core::ptr::addr_of_mut;
@ -28,7 +27,7 @@ use esp_hal::{
timer::timg::TimerGroup, timer::timg::TimerGroup,
}; };
use esp_println::println; use esp_println::println;
use static_cell::make_static; use static_cell::StaticCell;
static mut APP_CORE_STACK: Stack<8192> = Stack::new(); static mut APP_CORE_STACK: Stack<8192> = Stack::new();
@ -64,13 +63,15 @@ async fn main(_spawner: Spawner) {
let mut cpu_control = CpuControl::new(peripherals.CPU_CTRL); let mut cpu_control = CpuControl::new(peripherals.CPU_CTRL);
let led_ctrl_signal = &*make_static!(Signal::new()); static LED_CTRL: StaticCell<Signal<CriticalSectionRawMutex, bool>> = StaticCell::new();
let led_ctrl_signal = &*LED_CTRL.init(Signal::new());
let led = io.pins.gpio0.into_push_pull_output(); let led = io.pins.gpio0.into_push_pull_output();
let _guard = cpu_control let _guard = cpu_control
.start_app_core(unsafe { &mut *addr_of_mut!(APP_CORE_STACK) }, move || { .start_app_core(unsafe { &mut *addr_of_mut!(APP_CORE_STACK) }, move || {
let executor = make_static!(Executor::new()); static EXECUTOR: StaticCell<Executor> = StaticCell::new();
let executor = EXECUTOR.init(Executor::new());
executor.run(|spawner| { executor.run(|spawner| {
spawner.spawn(control_led(led, led_ctrl_signal)).ok(); spawner.spawn(control_led(led, led_ctrl_signal)).ok();
}); });

View File

@ -4,11 +4,10 @@
//! signal set by the task running on the other core. //! signal set by the task running on the other core.
//% CHIPS: esp32 esp32s3 //% CHIPS: esp32 esp32s3
//% FEATURES: embassy embassy-executor-interrupt embassy-time-timg0 embassy-generic-timers //% FEATURES: embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use core::ptr::addr_of_mut; use core::ptr::addr_of_mut;
@ -28,7 +27,7 @@ use esp_hal::{
timer::timg::TimerGroup, timer::timg::TimerGroup,
}; };
use esp_println::println; use esp_println::println;
use static_cell::make_static; use static_cell::StaticCell;
static mut APP_CORE_STACK: Stack<8192> = Stack::new(); static mut APP_CORE_STACK: Stack<8192> = Stack::new();
@ -83,29 +82,31 @@ fn main() -> ! {
let mut cpu_control = CpuControl::new(peripherals.CPU_CTRL); let mut cpu_control = CpuControl::new(peripherals.CPU_CTRL);
let led_ctrl_signal = &*make_static!(Signal::new()); static LED_CTRL: StaticCell<Signal<CriticalSectionRawMutex, bool>> = StaticCell::new();
let led_ctrl_signal = &*LED_CTRL.init(Signal::new());
let led = io.pins.gpio0.into_push_pull_output(); let led = io.pins.gpio0.into_push_pull_output();
static EXECUTOR_CORE_1: StaticCell<InterruptExecutor<1>> = StaticCell::new();
let executor_core1 = let executor_core1 =
InterruptExecutor::new(system.software_interrupt_control.software_interrupt1); InterruptExecutor::new(system.software_interrupt_control.software_interrupt1);
let executor_core1 = make_static!(executor_core1); let executor_core1 = EXECUTOR_CORE_1.init(executor_core1);
let cpu1_fnctn = move || {
let spawner = executor_core1.start(Priority::Priority1);
spawner.spawn(control_led(led, led_ctrl_signal)).ok();
// Just loop to show that the main thread does not need to poll the executor.
loop {}
};
let _guard = cpu_control let _guard = cpu_control
.start_app_core(unsafe { &mut *addr_of_mut!(APP_CORE_STACK) }, cpu1_fnctn) .start_app_core(unsafe { &mut *addr_of_mut!(APP_CORE_STACK) }, move || {
let spawner = executor_core1.start(Priority::Priority1);
spawner.spawn(control_led(led, led_ctrl_signal)).ok();
// Just loop to show that the main thread does not need to poll the executor.
loop {}
})
.unwrap(); .unwrap();
static EXECUTOR_CORE_0: StaticCell<InterruptExecutor<0>> = StaticCell::new();
let executor_core0 = let executor_core0 =
InterruptExecutor::new(system.software_interrupt_control.software_interrupt0); InterruptExecutor::new(system.software_interrupt_control.software_interrupt0);
let executor_core0 = make_static!(executor_core0); let executor_core0 = EXECUTOR_CORE_0.init(executor_core0);
let spawner = executor_core0.start(Priority::Priority1); let spawner = executor_core0.start(Priority::Priority1);
spawner.spawn(enable_disable_led(led_ctrl_signal)).ok(); spawner.spawn(enable_disable_led(led_ctrl_signal)).ok();

View File

@ -16,11 +16,10 @@
// The interrupt-executor is created in `main` and is used to spawn `high_prio`. // The interrupt-executor is created in `main` and is used to spawn `high_prio`.
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: embassy embassy-executor-interrupt embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_time::{Duration, Instant, Ticker, Timer}; use embassy_time::{Duration, Instant, Ticker, Timer};
@ -35,7 +34,7 @@ use esp_hal::{
timer::timg::TimerGroup, timer::timg::TimerGroup,
}; };
use esp_println::println; use esp_println::println;
use static_cell::make_static; use static_cell::StaticCell;
/// Periodically print something. /// Periodically print something.
#[embassy_executor::task] #[embassy_executor::task]
@ -83,8 +82,9 @@ async fn main(low_prio_spawner: Spawner) {
let timg0 = TimerGroup::new_async(peripherals.TIMG0, &clocks); let timg0 = TimerGroup::new_async(peripherals.TIMG0, &clocks);
embassy::init(&clocks, timg0); embassy::init(&clocks, timg0);
static EXECUTOR: StaticCell<InterruptExecutor<2>> = StaticCell::new();
let executor = InterruptExecutor::new(system.software_interrupt_control.software_interrupt2); let executor = InterruptExecutor::new(system.software_interrupt_control.software_interrupt2);
let executor = make_static!(executor); let executor = EXECUTOR.init(executor);
let spawner = executor.start(Priority::Priority3); let spawner = executor.start(Priority::Priority3);
spawner.must_spawn(high_prio()); spawner.must_spawn(high_prio());

View File

@ -4,11 +4,10 @@
//! Uses GPIO 1, 2, 3 and 4 as the data pins. //! Uses GPIO 1, 2, 3 and 4 as the data pins.
//% CHIPS: esp32c6 esp32h2 //% CHIPS: esp32c6 esp32h2
//% FEATURES: async embassy embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: async embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_time::{Duration, Timer}; use embassy_time::{Duration, Timer};

View File

@ -8,11 +8,10 @@
//! You can use a logic analyzer to see how the pins are used. //! You can use a logic analyzer to see how the pins are used.
//% CHIPS: esp32c6 esp32h2 //% CHIPS: esp32c6 esp32h2
//% FEATURES: async embassy embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: async embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_time::{Duration, Timer}; use embassy_time::{Duration, Timer};

View File

@ -2,11 +2,10 @@
//! Connect GPIO5 to GPIO4 //! Connect GPIO5 to GPIO4
//% CHIPS: esp32 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% CHIPS: esp32 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: async embassy embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: async embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_time::{Duration, Timer}; use embassy_time::{Duration, Timer};

View File

@ -3,11 +3,10 @@
//! Connect a logic analyzer to GPIO4 to see the generated pulses. //! Connect a logic analyzer to GPIO4 to see the generated pulses.
//% CHIPS: esp32 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% CHIPS: esp32 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: async embassy embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: async embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_time::{Duration, Timer}; use embassy_time::{Duration, Timer};

View File

@ -5,10 +5,9 @@
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: async embassy embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: async embassy embassy-time-timg0 embassy-generic-timers
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_sync::{blocking_mutex::raw::NoopRawMutex, signal::Signal}; use embassy_sync::{blocking_mutex::raw::NoopRawMutex, signal::Signal};
@ -23,7 +22,7 @@ use esp_hal::{
uart::{config::AtCmdConfig, Uart, UartRx, UartTx}, uart::{config::AtCmdConfig, Uart, UartRx, UartTx},
Async, Async,
}; };
use static_cell::make_static; use static_cell::StaticCell;
// rx_fifo_full_threshold // rx_fifo_full_threshold
const READ_BUF_SIZE: usize = 64; const READ_BUF_SIZE: usize = 64;
@ -91,7 +90,8 @@ async fn main(spawner: Spawner) {
.unwrap(); .unwrap();
let (tx, rx) = uart0.split(); let (tx, rx) = uart0.split();
let signal = &*make_static!(Signal::new()); static SIGNAL: StaticCell<Signal<NoopRawMutex, usize>> = StaticCell::new();
let signal = &*SIGNAL.init(Signal::new());
spawner.spawn(reader(rx, &signal)).ok(); spawner.spawn(reader(rx, &signal)).ok();
spawner.spawn(writer(tx, &signal)).ok(); spawner.spawn(writer(tx, &signal)).ok();

View File

@ -15,11 +15,10 @@
//! This is an example of running the embassy executor with SPI. //! This is an example of running the embassy executor with SPI.
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: async embassy embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: async embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_time::{Duration, Timer}; use embassy_time::{Duration, Timer};

View File

@ -3,11 +3,10 @@
//! This is an example of using the `DelayNs` trait implementation //! This is an example of using the `DelayNs` trait implementation
//% CHIPS: esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% CHIPS: esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: embassy embassy-time-timg0 embassy-executor-thread embassy-generic-timers async //% FEATURES: embassy embassy-time-timg0 embassy-generic-timers async
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embedded_hal_async::delay::DelayNs; use embedded_hal_async::delay::DelayNs;

View File

@ -11,11 +11,10 @@
//! with `IS_SENDER` set to `true`. //! with `IS_SENDER` set to `true`.
//% CHIPS: esp32c3 esp32c6 esp32s2 esp32s3 //% CHIPS: esp32c3 esp32c6 esp32s2 esp32s3
//% FEATURES: async embassy embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: async embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_sync::{blocking_mutex::raw::NoopRawMutex, channel::Channel}; use embassy_sync::{blocking_mutex::raw::NoopRawMutex, channel::Channel};
@ -33,7 +32,7 @@ use esp_hal::{
twai::{self, EspTwaiFrame, TwaiRx, TwaiTx}, twai::{self, EspTwaiFrame, TwaiRx, TwaiTx},
}; };
use esp_println::println; use esp_println::println;
use static_cell::make_static; use static_cell::StaticCell;
type TwaiOutbox = Channel<NoopRawMutex, EspTwaiFrame, 16>; type TwaiOutbox = Channel<NoopRawMutex, EspTwaiFrame, 16>;
@ -133,7 +132,8 @@ async fn main(spawner: Spawner) {
) )
.unwrap(); .unwrap();
let channel = &*make_static!(Channel::new()); static CHANNEL: StaticCell<TwaiOutbox> = StaticCell::new();
let channel = &*CHANNEL.init(Channel::new());
spawner.spawn(receiver(rx, channel)).ok(); spawner.spawn(receiver(rx, channel)).ok();
spawner.spawn(transmitter(tx, channel)).ok(); spawner.spawn(transmitter(tx, channel)).ok();

View File

@ -3,7 +3,7 @@
//! This example should be built in release mode. //! This example should be built in release mode.
//% CHIPS: esp32s2 esp32s3 //% CHIPS: esp32s2 esp32s3
//% FEATURES: async embassy embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: async embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]

View File

@ -3,11 +3,10 @@
//! Most dev-kits use a USB-UART-bridge - in that case you won't see any output. //! Most dev-kits use a USB-UART-bridge - in that case you won't see any output.
//% CHIPS: esp32c3 esp32c6 esp32h2 esp32s3 //% CHIPS: esp32c3 esp32c6 esp32h2 esp32s3
//% FEATURES: async embassy embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: async embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_sync::{blocking_mutex::raw::NoopRawMutex, signal::Signal}; use embassy_sync::{blocking_mutex::raw::NoopRawMutex, signal::Signal};
@ -22,7 +21,7 @@ use esp_hal::{
usb_serial_jtag::{UsbSerialJtag, UsbSerialJtagRx, UsbSerialJtagTx}, usb_serial_jtag::{UsbSerialJtag, UsbSerialJtagRx, UsbSerialJtagTx},
Async, Async,
}; };
use static_cell::make_static; use static_cell::StaticCell;
const MAX_BUFFER_SIZE: usize = 512; const MAX_BUFFER_SIZE: usize = 512;
@ -76,7 +75,9 @@ async fn main(spawner: Spawner) -> () {
let (tx, rx) = UsbSerialJtag::new_async(peripherals.USB_DEVICE).split(); let (tx, rx) = UsbSerialJtag::new_async(peripherals.USB_DEVICE).split();
let signal = &*make_static!(Signal::new()); static SIGNAL: StaticCell<Signal<NoopRawMutex, heapless::String<MAX_BUFFER_SIZE>>> =
StaticCell::new();
let signal = &*SIGNAL.init(Signal::new());
spawner.spawn(reader(rx, &signal)).unwrap(); spawner.spawn(reader(rx, &signal)).unwrap();
spawner.spawn(writer(tx, &signal)).unwrap(); spawner.spawn(writer(tx, &signal)).unwrap();

View File

@ -3,11 +3,10 @@
//! This is an example of asynchronously `Wait`ing for a pin state to change. //! This is an example of asynchronously `Wait`ing for a pin state to change.
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: async embassy embassy-executor-thread embassy-time-timg0 embassy-generic-timers //% FEATURES: async embassy embassy-time-timg0 embassy-generic-timers
#![no_std] #![no_std]
#![no_main] #![no_main]
#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_time::{Duration, Timer}; use embassy_time::{Duration, Timer};

View File

@ -88,7 +88,7 @@ p192 = { version = "0.13.0", default-features = false, features =
p256 = { version = "0.13.2", default-features = false, features = ["arithmetic"] } p256 = { version = "0.13.2", default-features = false, features = ["arithmetic"] }
[features] [features]
default = ["async", "embassy", "embassy-executor-thread", "embassy-time-timg0"] default = ["async", "embassy", "embassy-time-timg0"]
# Device support (required!): # Device support (required!):
esp32 = [ esp32 = [
@ -117,8 +117,6 @@ embassy = [
"embedded-test/external-executor", "embedded-test/external-executor",
"esp-hal?/embassy", "esp-hal?/embassy",
] ]
embassy-executor-interrupt = ["esp-hal?/embassy-executor-interrupt"]
embassy-executor-thread = ["esp-hal?/embassy-executor-thread"]
embassy-time-systick-16mhz = ["esp-hal?/embassy-time-systick-16mhz"] embassy-time-systick-16mhz = ["esp-hal?/embassy-time-systick-16mhz"]
embassy-time-systick-80mhz = ["esp-hal?/embassy-time-systick-80mhz"] embassy-time-systick-80mhz = ["esp-hal?/embassy-time-systick-80mhz"]
embassy-time-timg0 = ["esp-hal?/embassy-time-timg0"] embassy-time-timg0 = ["esp-hal?/embassy-time-timg0"]

View File

@ -71,7 +71,7 @@ pub fn interrupt_handler() {
} }
#[cfg(test)] #[cfg(test)]
#[embedded_test::tests(executor = esp_hal::embassy::executor::thread::Executor::new())] #[embedded_test::tests(executor = esp_hal::embassy::executor::Executor::new())]
mod tests { mod tests {
use defmt::assert_eq; use defmt::assert_eq;
use embassy_time::{Duration, Timer}; use embassy_time::{Duration, Timer};

View File

@ -47,7 +47,7 @@ impl Context {
} }
#[cfg(test)] #[cfg(test)]
#[embedded_test::tests(executor = esp_hal::embassy::executor::thread::Executor::new())] #[embedded_test::tests(executor = esp_hal::embassy::executor::Executor::new())]
mod tests { mod tests {
use defmt::assert_eq; use defmt::assert_eq;