Skip to content

Commit

Permalink
Make interrupt-executor require a SoftwareInterrupt<n>
Browse files Browse the repository at this point in the history
  • Loading branch information
bjoernQ committed Apr 4, 2024
1 parent 3d98d2f commit 6591237
Show file tree
Hide file tree
Showing 7 changed files with 183 additions and 219 deletions.
201 changes: 95 additions & 106 deletions esp-hal/src/embassy/executor/interrupt.rs
Original file line number Diff line number Diff line change
@@ -1,128 +1,109 @@
//! Interrupt-mode executor.
use core::{cell::UnsafeCell, marker::PhantomData, mem::MaybeUninit};
use core::{cell::UnsafeCell, mem::MaybeUninit};

use embassy_executor::{raw, SendSpawner};
#[cfg(any(esp32c6, esp32h2))]
use peripherals::INTPRI as SystemPeripheral;
#[cfg(not(any(esp32c6, esp32h2)))]
use peripherals::SYSTEM as SystemPeripheral;
use portable_atomic::{AtomicUsize, Ordering};

use crate::{get_core, interrupt, peripherals};
use crate::{
get_core,
interrupt::{self, InterruptHandler},
system::SoftwareInterrupt,
};

static FROM_CPU_IRQ_USED: AtomicUsize = AtomicUsize::new(0);

pub trait SwPendableInterrupt {
fn enable(priority: interrupt::Priority);
fn number() -> usize;
fn pend();
fn clear();
}

macro_rules! from_cpu {
($irq:literal) => {
paste::paste! {
pub struct [<FromCpu $irq>];

impl [<FromCpu $irq>] {
fn set_bit(value: bool) {
let system = unsafe { &*SystemPeripheral::PTR };

system
.[<cpu_intr_from_cpu_ $irq>]()
.write(|w| w.[<cpu_intr_from_cpu_ $irq>]().bit(value));
}
}

impl SwPendableInterrupt for [<FromCpu $irq>] {
fn enable(priority: interrupt::Priority) {
let mask = 1 << $irq;
// We don't allow using the same interrupt for multiple executors.
if FROM_CPU_IRQ_USED.fetch_or(mask, Ordering::SeqCst) & mask != 0 {
panic!("FROM_CPU_{} is already used by a different executor.", $irq);
}

unwrap!(interrupt::enable(peripherals::Interrupt::[<FROM_CPU_INTR $irq>], priority));
}

fn number() -> usize {
$irq
}

fn pend() {
Self::set_bit(true);
}

fn clear() {
Self::set_bit(false);
}
}
}
};
}

// from_cpu!(0); // reserve 0 for thread mode & multi-core
from_cpu!(1);
from_cpu!(2);
from_cpu!(3);
static mut EXECUTORS: [CallbackContext; 4] = [
CallbackContext::new(),
CallbackContext::new(),
CallbackContext::new(),
CallbackContext::new(),
];

/// Interrupt mode executor.
///
/// This executor runs tasks in interrupt mode. The interrupt handler is set up
/// to poll tasks, and when a task is woken the interrupt is pended from
/// software.
///
/// # Interrupt requirements
///
/// You must write the interrupt handler yourself, and make it call
/// [`Self::on_interrupt()`]
///
/// ```rust,ignore
/// #[interrupt]
/// fn FROM_CPU_INTR1() {
/// unsafe { INT_EXECUTOR.on_interrupt() }
/// }
/// ```
pub struct InterruptExecutor<SWI>
where
SWI: SwPendableInterrupt,
{
pub struct InterruptExecutor<const SWI: u8> {
core: AtomicUsize,
executor: UnsafeCell<MaybeUninit<raw::Executor>>,
_interrupt: PhantomData<SWI>,
interrupt: SoftwareInterrupt<SWI>,
}

unsafe impl<const SWI: u8> Send for InterruptExecutor<SWI> {}
unsafe impl<const SWI: u8> Sync for InterruptExecutor<SWI> {}

struct CallbackContext {
raw_executor: UnsafeCell<*mut raw::Executor>,
}

impl CallbackContext {
const fn new() -> Self {
Self {
raw_executor: UnsafeCell::new(core::ptr::null_mut()),
}
}

fn get(&self) -> *mut raw::Executor {
unsafe { (*self.raw_executor.get()) as *mut raw::Executor }
}

fn set(&self, executor: *mut raw::Executor) {
unsafe {
self.raw_executor.get().write(executor);
}
}
}

unsafe impl<SWI: SwPendableInterrupt> Send for InterruptExecutor<SWI> {}
unsafe impl<SWI: SwPendableInterrupt> Sync for InterruptExecutor<SWI> {}
extern "C" fn swi_handler0() {
let mut swi = unsafe { SoftwareInterrupt::<0>::steal() };
swi.reset();

impl<SWI> InterruptExecutor<SWI>
where
SWI: SwPendableInterrupt,
{
unsafe {
let executor = EXECUTORS[0].get().as_mut().unwrap();
executor.poll();
}
}

extern "C" fn swi_handler1() {
let mut swi = unsafe { SoftwareInterrupt::<1>::steal() };
swi.reset();

unsafe {
let executor = EXECUTORS[1].get().as_mut().unwrap();
executor.poll();
}
}

extern "C" fn swi_handler2() {
let mut swi = unsafe { SoftwareInterrupt::<2>::steal() };
swi.reset();

unsafe {
let executor = EXECUTORS[2].get().as_mut().unwrap();
executor.poll();
}
}

extern "C" fn swi_handler3() {
let mut swi = unsafe { SoftwareInterrupt::<3>::steal() };
swi.reset();

unsafe {
let executor = EXECUTORS[3].get().as_mut().unwrap();
executor.poll();
}
}

impl<const SWI: u8> InterruptExecutor<SWI> {
/// Create a new `InterruptExecutor`.
#[inline]
pub const fn new() -> Self {
pub const fn new(interrupt: SoftwareInterrupt<SWI>) -> Self {
Self {
core: AtomicUsize::new(usize::MAX),
executor: UnsafeCell::new(MaybeUninit::uninit()),
_interrupt: PhantomData,
interrupt,
}
}

/// Executor interrupt callback.
///
/// # Safety
///
/// You MUST call this from the interrupt handler, and from nowhere else.
// TODO: it would be pretty sweet if we could register our own interrupt handler
// when vectoring is enabled. The user shouldn't need to provide the handler for
// us.
pub unsafe fn on_interrupt(&'static self) {
SWI::clear();
let executor = unsafe { (*self.executor.get()).assume_init_ref() };
executor.poll();
}

/// Start the executor at the given priority level.
///
/// This initializes the executor, enables the interrupt, and returns.
Expand All @@ -141,12 +122,9 @@ where
/// You must write the interrupt handler yourself, and make it call
/// [`Self::on_interrupt()`]
///
/// This method already enables (unmasks) the interrupt, you must NOT do it
/// yourself.
///
/// [`Spawner`]: embassy_executor::Spawner
/// [`Spawner::for_current_executor()`]: embassy_executor::Spawner::for_current_executor()
pub fn start(&'static self, priority: interrupt::Priority) -> SendSpawner {
pub fn start(&'static mut self, priority: interrupt::Priority) -> SendSpawner {
if self
.core
.compare_exchange(
Expand All @@ -163,10 +141,21 @@ where
unsafe {
(*self.executor.get())
.as_mut_ptr()
.write(raw::Executor::new(SWI::number() as *mut ()))
.write(raw::Executor::new(SWI as *mut ()));

EXECUTORS[SWI as usize].set((*self.executor.get()).as_mut_ptr());
}

SWI::enable(priority);
let swi_handler = match SWI {
0 => swi_handler0,
1 => swi_handler1,
2 => swi_handler2,
3 => swi_handler3,
_ => unreachable!(),
};

self.interrupt
.set_interrupt_handler(InterruptHandler::new(swi_handler, priority));

let executor = unsafe { (*self.executor.get()).assume_init_ref() };
executor.spawner().make_send()
Expand Down
12 changes: 9 additions & 3 deletions esp-hal/src/embassy/executor/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -16,16 +16,22 @@ pub use interrupt::*;
))]
#[export_name = "__pender"]
fn __pender(context: *mut ()) {
#[cfg(feature = "embassy-executor-interrupt")]
use crate::system::SoftwareInterrupt;

let context = (context as usize).to_le_bytes();

cfg_if::cfg_if! {
if #[cfg(feature = "embassy-executor-interrupt")] {
match context[0] {
#[cfg(feature = "embassy-executor-thread")]
0 => thread::pend_thread_mode(context[1] as usize),
1 => FromCpu1::pend(),
2 => FromCpu2::pend(),
3 => FromCpu3::pend(),

#[cfg(not(feature = "embassy-executor-thread"))]
0 => unsafe { SoftwareInterrupt::<0>::steal().raise() },
1 => unsafe { SoftwareInterrupt::<1>::steal().raise() },
2 => unsafe { SoftwareInterrupt::<2>::steal().raise() },
3 => unsafe { SoftwareInterrupt::<3>::steal().raise() },
_ => {}
}
} else {
Expand Down
18 changes: 9 additions & 9 deletions examples/src/bin/direct_vectoring.rs
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,10 @@ use esp_hal::{
interrupt::{self, CpuInterrupt, Priority},
peripherals::{Interrupt, Peripherals},
prelude::*,
system::{SoftwareInterrupt, SoftwareInterruptControl},
system::SoftwareInterrupt,
};

static SWINT: Mutex<RefCell<Option<SoftwareInterruptControl>>> = Mutex::new(RefCell::new(None));
static SWINT0: Mutex<RefCell<Option<SoftwareInterrupt<0>>>> = Mutex::new(RefCell::new(None));

#[entry]
fn main() -> ! {
Expand All @@ -31,7 +31,11 @@ fn main() -> ! {
let system = peripherals.SYSTEM.split();
let sw_int = system.software_interrupt_control;

critical_section::with(|cs| SWINT.borrow_ref_mut(cs).replace(sw_int));
critical_section::with(|cs| {
SWINT0
.borrow_ref_mut(cs)
.replace(sw_int.software_interrupt0)
});
interrupt::enable_direct(
Interrupt::FROM_CPU_INTR0,
Priority::Priority3,
Expand Down Expand Up @@ -67,14 +71,10 @@ fn main() -> ! {
}

#[no_mangle]
fn cpu_int_20_handler() {
fn interrupt20() {
unsafe { asm!("csrrwi x0, 0x7e1, 0 #disable timer") }
critical_section::with(|cs| {
SWINT
.borrow_ref_mut(cs)
.as_mut()
.unwrap()
.reset(SoftwareInterrupt::SoftwareInterrupt0);
SWINT0.borrow_ref_mut(cs).as_mut().unwrap().reset();
});

let mut perf_counter: u32 = 0;
Expand Down
32 changes: 12 additions & 20 deletions examples/src/bin/embassy_multicore_interrupt.rs
Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,11 @@ use core::ptr::addr_of_mut;

use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, signal::Signal};
use embassy_time::{Duration, Ticker};
use embedded_hal_02::digital::v2::OutputPin;
use esp_backtrace as _;
use esp_hal::{
clock::ClockControl,
cpu_control::{CpuControl, Stack},
embassy::{
self,
executor::{FromCpu1, FromCpu2, InterruptExecutor},
},
embassy::{self, executor::InterruptExecutor},
get_core,
gpio::{GpioPin, Output, PushPull, IO},
interrupt::Priority,
Expand All @@ -35,19 +31,6 @@ use static_cell::make_static;

static mut APP_CORE_STACK: Stack<8192> = Stack::new();

static INT_EXECUTOR_CORE_0: InterruptExecutor<FromCpu1> = InterruptExecutor::new();
static INT_EXECUTOR_CORE_1: InterruptExecutor<FromCpu2> = InterruptExecutor::new();

#[interrupt]
fn FROM_CPU_INTR1() {
unsafe { INT_EXECUTOR_CORE_0.on_interrupt() }
}

#[interrupt]
fn FROM_CPU_INTR2() {
unsafe { INT_EXECUTOR_CORE_1.on_interrupt() }
}

/// Waits for a message that contains a duration, then flashes a led for that
/// duration of time.
#[embassy_executor::task]
Expand Down Expand Up @@ -102,8 +85,13 @@ fn main() -> ! {
let led_ctrl_signal = &*make_static!(Signal::new());

let led = io.pins.gpio0.into_push_pull_output();

let executor_core1 =
InterruptExecutor::new(system.software_interrupt_control.software_interrupt1);
let executor_core1 = make_static!(executor_core1);

let cpu1_fnctn = move || {
let spawner = INT_EXECUTOR_CORE_1.start(Priority::Priority1);
let spawner = executor_core1.start(Priority::Priority1);

spawner.spawn(control_led(led, led_ctrl_signal)).ok();

Expand All @@ -114,7 +102,11 @@ fn main() -> ! {
.start_app_core(unsafe { &mut *addr_of_mut!(APP_CORE_STACK) }, cpu1_fnctn)
.unwrap();

let spawner = INT_EXECUTOR_CORE_0.start(Priority::Priority1);
let executor_core0 =
InterruptExecutor::new(system.software_interrupt_control.software_interrupt0);
let executor_core0 = make_static!(executor_core0);

let spawner = executor_core0.start(Priority::Priority1);
spawner.spawn(enable_disable_led(led_ctrl_signal)).ok();

// Just loop to show that the main thread does not need to poll the executor.
Expand Down
Loading

0 comments on commit 6591237

Please sign in to comment.