nrf/uarte: update to new api

This commit is contained in:
Dario Nieuwenhuis 2021-03-22 01:15:44 +01:00
parent 7b6086d19e
commit df42c38492
5 changed files with 267 additions and 264 deletions

View File

@ -12,38 +12,26 @@ use cortex_m_rt::entry;
use defmt::panic; use defmt::panic;
use embassy::executor::{task, Executor}; use embassy::executor::{task, Executor};
use embassy::time::{Duration, Timer}; use embassy::time::{Duration, Timer};
use embassy::traits::uart::Uart; use embassy::traits::uart::{Read, Write};
use embassy::util::Forever; use embassy::util::Forever;
use embassy_nrf::{interrupt, pac, rtc, uarte}; use embassy_nrf::{interrupt, pac, rtc, uarte, Peripherals};
use futures::future::{select, Either}; use futures::future::{select, Either};
use futures::pin_mut;
use nrf52840_hal::clocks; use nrf52840_hal::clocks;
use nrf52840_hal::gpio; use nrf52840_hal::gpio;
#[task] #[task]
async fn run(uart: pac::UARTE0, port: pac::P0) { async fn run() {
// Init UART let p = Peripherals::take().unwrap();
let port0 = gpio::p0::Parts::new(port);
let pins = uarte::Pins { let mut config = uarte::Config::default();
rxd: port0.p0_08.into_floating_input().degrade(), config.parity = uarte::Parity::EXCLUDED;
txd: port0 config.baudrate = uarte::Baudrate::BAUD115200;
.p0_06
.into_push_pull_output(gpio::Level::Low)
.degrade(),
cts: None,
rts: None,
};
// NOTE(unsafe): Safe becasue we do not use `mem::forget` anywhere. let irq = interrupt::take!(UARTE0_UART0);
let mut uart = unsafe { let uart =
uarte::Uarte::new( unsafe { uarte::Uarte::new(p.uarte0, irq, p.p0_08, p.p0_06, p.p0_07, p.p0_05, config) };
uart, pin_mut!(uart);
interrupt::take!(UARTE0_UART0),
pins,
uarte::Parity::EXCLUDED,
uarte::Baudrate::BAUD115200,
)
};
info!("uarte initialized!"); info!("uarte initialized!");
@ -51,19 +39,22 @@ async fn run(uart: pac::UARTE0, port: pac::P0) {
let mut buf = [0; 8]; let mut buf = [0; 8];
buf.copy_from_slice(b"Hello!\r\n"); buf.copy_from_slice(b"Hello!\r\n");
unwrap!(uart.send(&buf).await); unwrap!(uart.as_mut().write(&buf).await);
info!("wrote hello in uart!"); info!("wrote hello in uart!");
loop { loop {
let buf_len = buf.len();
info!("reading..."); info!("reading...");
unwrap!(uart.as_mut().read(&mut buf).await);
info!("writing...");
unwrap!(uart.as_mut().write(&buf).await);
/*
// `receive()` doesn't return until the buffer has been completely filled with // `receive()` doesn't return until the buffer has been completely filled with
// incoming data, which in this case is 8 bytes. // incoming data, which in this case is 8 bytes.
// //
// This example shows how to use `select` to run an uart receive concurrently with a // This example shows how to use `select` to run an uart receive concurrently with a
// 1 second timer, effectively adding a timeout to the receive operation. // 1 second timer, effectively adding a timeout to the receive operation.
let recv_fut = uart.receive(&mut buf); let recv_fut = uart.read(&mut buf);
let timer_fut = Timer::after(Duration::from_millis(1000)); let timer_fut = Timer::after(Duration::from_millis(1000));
let received_len = match select(recv_fut, timer_fut).await { let received_len = match select(recv_fut, timer_fut).await {
// recv_fut completed first, so we've received `buf_len` bytes. // recv_fut completed first, so we've received `buf_len` bytes.
@ -81,8 +72,9 @@ async fn run(uart: pac::UARTE0, port: pac::P0) {
info!("read done, got {}", received); info!("read done, got {}", received);
// Echo back received data // Echo back received data
unwrap!(uart.send(received).await); unwrap!(uart.write(received).await);
} }
*/
} }
} }
@ -110,9 +102,7 @@ fn main() -> ! {
let executor = EXECUTOR.put(Executor::new()); let executor = EXECUTOR.put(Executor::new());
executor.set_alarm(alarm); executor.set_alarm(alarm);
let uarte0 = p.UARTE0;
let p0 = p.P0;
executor.run(|spawner| { executor.run(|spawner| {
unwrap!(spawner.spawn(run(uarte0, p0))); unwrap!(spawner.spawn(run()));
}); });
} }

View File

@ -5,43 +5,49 @@
//! are dropped correctly (e.g. not using `mem::forget()`). //! are dropped correctly (e.g. not using `mem::forget()`).
use core::future::Future; use core::future::Future;
use core::ops::Deref; use core::marker::PhantomData;
use core::pin::Pin;
use core::sync::atomic::{compiler_fence, Ordering}; use core::sync::atomic::{compiler_fence, Ordering};
use core::task::{Context, Poll}; use core::task::Poll;
use embassy::traits::uart::{Error, Read, Write};
use embassy::interrupt::InterruptExt; use embassy::util::{wake_on_interrupt, OnDrop, PeripheralBorrow, Signal};
use embassy::util::Signal; use embassy_extras::unborrow;
use futures::future::poll_fn;
use crate::fmt::{assert, *}; use crate::fmt::{assert, *};
use crate::gpio::Pin as GpioPin;
use crate::hal::pac; use crate::hal::pac;
use crate::hal::prelude::*;
use crate::hal::target_constants::EASY_DMA_SIZE; use crate::hal::target_constants::EASY_DMA_SIZE;
use crate::interrupt; use crate::interrupt;
use crate::interrupt::Interrupt; use crate::interrupt::Interrupt;
use crate::peripherals;
pub use crate::hal::uarte::Pins;
// Re-export SVD variants to allow user to directly set values. // Re-export SVD variants to allow user to directly set values.
pub use pac::uarte0::{baudrate::BAUDRATE_A as Baudrate, config::PARITY_A as Parity}; pub use pac::uarte0::{baudrate::BAUDRATE_A as Baudrate, config::PARITY_A as Parity};
#[non_exhaustive]
pub struct Config {
pub parity: Parity,
pub baudrate: Baudrate,
}
impl Default for Config {
fn default() -> Self {
Self {
parity: Parity::EXCLUDED,
baudrate: Baudrate::BAUD115200,
}
}
}
/// Interface to the UARTE peripheral /// Interface to the UARTE peripheral
pub struct Uarte<T> pub struct Uarte<'d, T: Instance> {
where peri: T,
T: Instance,
{
instance: T,
irq: T::Interrupt, irq: T::Interrupt,
pins: Pins, phantom: PhantomData<&'d mut T>,
} }
pub struct State { impl<'d, T: Instance> Uarte<'d, T> {
tx_done: Signal<()>,
rx_done: Signal<u32>,
}
impl<T> Uarte<T>
where
T: Instance,
{
/// Creates the interface to a UARTE instance. /// Creates the interface to a UARTE instance.
/// Sets the baud rate, parity and assigns the pins to the UARTE peripheral. /// Sets the baud rate, parity and assigns the pins to the UARTE peripheral.
/// ///
@ -52,85 +58,48 @@ where
/// or [`receive`](Uarte::receive). /// or [`receive`](Uarte::receive).
#[allow(unused_unsafe)] #[allow(unused_unsafe)]
pub unsafe fn new( pub unsafe fn new(
uarte: T, uarte: impl PeripheralBorrow<Target = T> + 'd,
irq: T::Interrupt, irq: impl PeripheralBorrow<Target = T::Interrupt> + 'd,
mut pins: Pins, rxd: impl PeripheralBorrow<Target = impl GpioPin> + 'd,
parity: Parity, txd: impl PeripheralBorrow<Target = impl GpioPin> + 'd,
baudrate: Baudrate, cts: impl PeripheralBorrow<Target = impl GpioPin> + 'd,
rts: impl PeripheralBorrow<Target = impl GpioPin> + 'd,
config: Config,
) -> Self { ) -> Self {
assert!(uarte.enable.read().enable().is_disabled()); unborrow!(uarte, irq, rxd, txd, cts, rts);
uarte.psel.rxd.write(|w| { let r = uarte.regs();
unsafe { w.bits(pins.rxd.psel_bits()) };
w.connect().connected()
});
pins.txd.set_high().unwrap(); assert!(r.enable.read().enable().is_disabled());
uarte.psel.txd.write(|w| {
unsafe { w.bits(pins.txd.psel_bits()) };
w.connect().connected()
});
// Optional pins // TODO OptionalPin for RTS/CTS.
uarte.psel.cts.write(|w| {
if let Some(ref pin) = pins.cts {
unsafe { w.bits(pin.psel_bits()) };
w.connect().connected()
} else {
w.connect().disconnected()
}
});
uarte.psel.rts.write(|w| { txd.set_high();
if let Some(ref pin) = pins.rts { rts.set_high();
unsafe { w.bits(pin.psel_bits()) }; rxd.conf().write(|w| w.input().connect().drive().h0h1());
w.connect().connected() txd.conf().write(|w| w.dir().output().drive().h0h1());
} else { //cts.conf().write(|w| w.input().connect().drive().h0h1());
w.connect().disconnected() //rts.conf().write(|w| w.dir().output().drive().h0h1());
}
});
uarte.baudrate.write(|w| w.baudrate().variant(baudrate)); r.psel.rxd.write(|w| unsafe { w.bits(rxd.psel_bits()) });
uarte.config.write(|w| w.parity().variant(parity)); r.psel.txd.write(|w| unsafe { w.bits(txd.psel_bits()) });
//r.psel.cts.write(|w| unsafe { w.bits(cts.psel_bits()) });
//r.psel.rts.write(|w| unsafe { w.bits(rts.psel_bits()) });
// Enable interrupts r.baudrate.write(|w| w.baudrate().variant(config.baudrate));
uarte.events_endtx.reset(); r.config.write(|w| w.parity().variant(config.parity));
uarte.events_endrx.reset();
uarte
.intenset
.write(|w| w.endtx().set().txstopped().set().endrx().set().rxto().set());
// Register ISR // Enable
irq.set_handler(Self::on_irq); r.enable.write(|w| w.enable().enabled());
irq.unpend();
irq.enable();
Uarte { Self {
instance: uarte, peri: uarte,
irq, irq,
pins, phantom: PhantomData,
} }
} }
pub fn free(self) -> (T, T::Interrupt, Pins) { /*
// Wait for the peripheral to be disabled from the ISR.
while self.instance.enable.read().enable().is_enabled() {}
(self.instance, self.irq, self.pins)
}
fn enable(&mut self) {
trace!("enable");
self.instance.enable.write(|w| w.enable().enabled());
}
fn tx_started(&self) -> bool {
self.instance.events_txstarted.read().bits() != 0
}
fn rx_started(&self) -> bool {
self.instance.events_rxstarted.read().bits() != 0
}
unsafe fn on_irq(_ctx: *mut ()) { unsafe fn on_irq(_ctx: *mut ()) {
let uarte = &*pac::UARTE0::ptr(); let uarte = &*pac::UARTE0::ptr();
@ -186,54 +155,127 @@ where
uarte.enable.write(|w| w.enable().disabled()); uarte.enable.write(|w| w.enable().disabled());
} }
} }
*/
} }
impl<T: Instance> embassy::traits::uart::Uart for Uarte<T> { impl<'d, T: Instance> Read for Uarte<'d, T> {
type ReceiveFuture<'a> = ReceiveFuture<'a, T>; #[rustfmt::skip]
type SendFuture<'a> = SendFuture<'a, T>; type ReadFuture<'a> where Self: 'a = impl Future<Output = Result<(), Error>> + 'a;
/// Sends serial data. fn read<'a>(self: Pin<&'a mut Self>, rx_buffer: &'a mut [u8]) -> Self::ReadFuture<'a> {
/// async move {
/// `tx_buffer` is marked as static as per `embedded-dma` requirements. let this = unsafe { self.get_unchecked_mut() };
/// It it safe to use a buffer with a non static lifetime if memory is not
/// reused until the future has finished.
fn send<'a>(&'a mut self, tx_buffer: &'a [u8]) -> SendFuture<'a, T> {
// Panic if TX is running which can happen if the user has called
// `mem::forget()` on a previous future after polling it once.
assert!(!self.tx_started());
T::state().tx_done.reset(); let ptr = rx_buffer.as_ptr();
let len = rx_buffer.len();
assert!(len <= EASY_DMA_SIZE);
SendFuture { let r = this.peri.regs();
uarte: self,
buf: tx_buffer,
}
}
/// Receives serial data. let drop = OnDrop::new(move || {
/// info!("read drop: stopping");
/// The future is pending until the buffer is completely filled.
/// A common pattern is to use [`stop()`](ReceiveFuture::stop) to cancel
/// unfinished transfers after a timeout to prevent lockup when no more data
/// is incoming.
///
/// `rx_buffer` is marked as static as per `embedded-dma` requirements.
/// It it safe to use a buffer with a non static lifetime if memory is not
/// reused until the future has finished.
fn receive<'a>(&'a mut self, rx_buffer: &'a mut [u8]) -> ReceiveFuture<'a, T> {
// Panic if RX is running which can happen if the user has called
// `mem::forget()` on a previous future after polling it once.
assert!(!self.rx_started());
T::state().rx_done.reset(); r.intenclr.write(|w| w.endrx().clear());
r.tasks_stoprx.write(|w| unsafe { w.bits(1) });
ReceiveFuture { // TX is stopped almost instantly, spinning is fine.
uarte: self, while r.events_endrx.read().bits() == 0 {}
buf: rx_buffer, info!("read drop: stopped");
});
r.rxd.ptr.write(|w| unsafe { w.ptr().bits(ptr as u32) });
r.rxd.maxcnt.write(|w| unsafe { w.maxcnt().bits(len as _) });
r.events_endrx.reset();
r.intenset.write(|w| w.endrx().set());
compiler_fence(Ordering::SeqCst);
trace!("startrx");
r.tasks_startrx.write(|w| unsafe { w.bits(1) });
let irq = &mut this.irq;
poll_fn(|cx| {
if r.events_endrx.read().bits() != 0 {
r.events_endrx.reset();
return Poll::Ready(());
}
wake_on_interrupt(irq, cx.waker());
Poll::Pending
})
.await;
compiler_fence(Ordering::SeqCst);
r.intenclr.write(|w| w.endrx().clear());
drop.defuse();
Ok(())
} }
} }
} }
impl<'d, T: Instance> Write for Uarte<'d, T> {
#[rustfmt::skip]
type WriteFuture<'a> where Self: 'a = impl Future<Output = Result<(), Error>> + 'a;
fn write<'a>(self: Pin<&'a mut Self>, tx_buffer: &'a [u8]) -> Self::WriteFuture<'a> {
async move {
let this = unsafe { self.get_unchecked_mut() };
let ptr = tx_buffer.as_ptr();
let len = tx_buffer.len();
assert!(len <= EASY_DMA_SIZE);
// TODO: panic if buffer is not in SRAM
let r = this.peri.regs();
let drop = OnDrop::new(move || {
info!("write drop: stopping");
r.intenclr.write(|w| w.endtx().clear());
r.tasks_stoptx.write(|w| unsafe { w.bits(1) });
// TX is stopped almost instantly, spinning is fine.
while r.events_endtx.read().bits() == 0 {}
info!("write drop: stopped");
});
r.txd.ptr.write(|w| unsafe { w.ptr().bits(ptr as u32) });
r.txd.maxcnt.write(|w| unsafe { w.maxcnt().bits(len as _) });
r.events_endtx.reset();
r.intenset.write(|w| w.endtx().set());
compiler_fence(Ordering::SeqCst);
trace!("starttx");
r.tasks_starttx.write(|w| unsafe { w.bits(1) });
let irq = &mut this.irq;
poll_fn(|cx| {
if r.events_endtx.read().bits() != 0 {
r.events_endtx.reset();
return Poll::Ready(());
}
wake_on_interrupt(irq, cx.waker());
Poll::Pending
})
.await;
compiler_fence(Ordering::SeqCst);
r.intenclr.write(|w| w.endtx().clear());
drop.defuse();
Ok(())
}
}
}
/*
/// Future for the [`Uarte::send()`] method. /// Future for the [`Uarte::send()`] method.
pub struct SendFuture<'a, T> pub struct SendFuture<'a, T>
where where
@ -252,11 +294,8 @@ where
trace!("stoptx"); trace!("stoptx");
// Stop the transmitter to minimize the current consumption. // Stop the transmitter to minimize the current consumption.
self.uarte.instance.events_txstarted.reset(); self.uarte.peri.events_txstarted.reset();
self.uarte self.uarte.peri.tasks_stoptx.write(|w| unsafe { w.bits(1) });
.instance
.tasks_stoptx
.write(|w| unsafe { w.bits(1) });
// TX is stopped almost instantly, spinning is fine. // TX is stopped almost instantly, spinning is fine.
while !T::state().tx_done.signaled() {} while !T::state().tx_done.signaled() {}
@ -264,46 +303,6 @@ where
} }
} }
impl<'a, T> Future for SendFuture<'a, T>
where
T: Instance,
{
type Output = Result<(), embassy::traits::uart::Error>;
fn poll(self: core::pin::Pin<&mut Self>, cx: &mut Context<'_>) -> Poll<Self::Output> {
let Self { uarte, buf } = unsafe { self.get_unchecked_mut() };
if T::state().tx_done.poll_wait(cx).is_pending() {
let ptr = buf.as_ptr();
let len = buf.len();
assert!(len <= EASY_DMA_SIZE);
// TODO: panic if buffer is not in SRAM
uarte.enable();
compiler_fence(Ordering::SeqCst);
uarte
.instance
.txd
.ptr
.write(|w| unsafe { w.ptr().bits(ptr as u32) });
uarte
.instance
.txd
.maxcnt
.write(|w| unsafe { w.maxcnt().bits(len as _) });
trace!("starttx");
uarte.instance.tasks_starttx.write(|w| unsafe { w.bits(1) });
while !uarte.tx_started() {} // Make sure transmission has started
Poll::Pending
} else {
Poll::Ready(Ok(()))
}
}
}
/// Future for the [`Uarte::receive()`] method. /// Future for the [`Uarte::receive()`] method.
pub struct ReceiveFuture<'a, T> pub struct ReceiveFuture<'a, T>
where where
@ -321,11 +320,8 @@ where
if self.uarte.rx_started() { if self.uarte.rx_started() {
trace!("stoprx (drop)"); trace!("stoprx (drop)");
self.uarte.instance.events_rxstarted.reset(); self.uarte.peri.events_rxstarted.reset();
self.uarte self.uarte.peri.tasks_stoprx.write(|w| unsafe { w.bits(1) });
.instance
.tasks_stoprx
.write(|w| unsafe { w.bits(1) });
embassy_extras::low_power_wait_until(|| T::state().rx_done.signaled()) embassy_extras::low_power_wait_until(|| T::state().rx_done.signaled())
} }
@ -350,19 +346,11 @@ where
uarte.enable(); uarte.enable();
compiler_fence(Ordering::SeqCst); compiler_fence(Ordering::SeqCst);
uarte r.rxd.ptr.write(|w| unsafe { w.ptr().bits(ptr as u32) });
.instance r.rxd.maxcnt.write(|w| unsafe { w.maxcnt().bits(len as _) });
.rxd
.ptr
.write(|w| unsafe { w.ptr().bits(ptr as u32) });
uarte
.instance
.rxd
.maxcnt
.write(|w| unsafe { w.maxcnt().bits(len as _) });
trace!("startrx"); trace!("startrx");
uarte.instance.tasks_startrx.write(|w| unsafe { w.bits(1) }); uarte.peri.tasks_startrx.write(|w| unsafe { w.bits(1) });
while !uarte.rx_started() {} // Make sure reception has started while !uarte.rx_started() {} // Make sure reception has started
Poll::Pending Poll::Pending
@ -383,11 +371,8 @@ where
let len = if self.uarte.rx_started() { let len = if self.uarte.rx_started() {
trace!("stoprx (stop)"); trace!("stoprx (stop)");
self.uarte.instance.events_rxstarted.reset(); self.uarte.peri.events_rxstarted.reset();
self.uarte self.uarte.peri.tasks_stoprx.write(|w| unsafe { w.bits(1) });
.instance
.tasks_stoprx
.write(|w| unsafe { w.bits(1) });
T::state().rx_done.wait().await T::state().rx_done.wait().await
} else { } else {
// Transfer was stopped before it even started. No bytes were sent. // Transfer was stopped before it even started. No bytes were sent.
@ -396,45 +381,33 @@ where
len as _ len as _
} }
} }
*/
mod private { mod sealed {
pub trait Sealed {} use super::*;
pub trait Instance {
fn regs(&self) -> &pac::uarte0::RegisterBlock;
}
} }
pub trait Instance: pub trait Instance: sealed::Instance + 'static {
Deref<Target = pac::uarte0::RegisterBlock> + Sized + private::Sealed + 'static
{
type Interrupt: Interrupt; type Interrupt: Interrupt;
#[doc(hidden)]
fn state() -> &'static State;
} }
static UARTE0_STATE: State = State { macro_rules! make_impl {
tx_done: Signal::new(), ($type:ident, $irq:ident) => {
rx_done: Signal::new(), impl sealed::Instance for peripherals::$type {
}; fn regs(&self) -> &pac::uarte0::RegisterBlock {
impl private::Sealed for pac::UARTE0 {} unsafe { &*pac::$type::ptr() }
impl Instance for pac::UARTE0 { }
type Interrupt = interrupt::UARTE0_UART0; }
impl Instance for peripherals::$type {
fn state() -> &'static State { type Interrupt = interrupt::$irq;
&UARTE0_STATE }
} };
} }
make_impl!(UARTE0, UARTE0_UART0);
#[cfg(any(feature = "52833", feature = "52840", feature = "9160"))] #[cfg(any(feature = "52833", feature = "52840", feature = "9160"))]
static UARTE1_STATE: State = State { make_impl!(UARTE1, UARTE1);
tx_done: Signal::new(),
rx_done: Signal::new(),
};
#[cfg(any(feature = "52833", feature = "52840", feature = "9160"))]
impl private::Sealed for pac::UARTE1 {}
#[cfg(any(feature = "52833", feature = "52840", feature = "9160"))]
impl Instance for pac::UARTE1 {
type Interrupt = interrupt::UARTE1;
fn state() -> &'static State {
&UARTE1_STATE
}
}

View File

@ -1,4 +1,5 @@
use core::future::Future; use core::future::Future;
use core::pin::Pin;
#[derive(Copy, Clone, Debug, Eq, PartialEq)] #[derive(Copy, Clone, Debug, Eq, PartialEq)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))] #[cfg_attr(feature = "defmt", derive(defmt::Format))]
@ -7,18 +8,31 @@ pub enum Error {
Other, Other,
} }
pub trait Uart { pub trait Read {
type ReceiveFuture<'a>: Future<Output = Result<(), Error>>; type ReadFuture<'a>: Future<Output = Result<(), Error>>
type SendFuture<'a>: Future<Output = Result<(), Error>>; where
/// Receive into the buffer until the buffer is full Self: 'a;
fn receive<'a>(&'a mut self, buf: &'a mut [u8]) -> Self::ReceiveFuture<'a>;
/// Send the specified buffer, and return when the transmission has completed fn read<'a>(self: Pin<&'a mut Self>, buf: &'a mut [u8]) -> Self::ReadFuture<'a>;
fn send<'a>(&'a mut self, buf: &'a [u8]) -> Self::SendFuture<'a>;
} }
pub trait IdleUart { pub trait ReadUntilIdle {
type ReceiveFuture<'a>: Future<Output = Result<usize, Error>>; type ReadUntilIdleFuture<'a>: Future<Output = Result<usize, Error>>
where
Self: 'a;
/// Receive into the buffer until the buffer is full or the line is idle after some bytes are received /// Receive into the buffer until the buffer is full or the line is idle after some bytes are received
/// Return the number of bytes received /// Return the number of bytes received
fn receive_until_idle<'a>(&'a mut self, buf: &'a mut [u8]) -> Self::ReceiveFuture<'a>; fn read_until_idle<'a>(
self: Pin<&'a mut Self>,
buf: &'a mut [u8],
) -> Self::ReadUntilIdleFuture<'a>;
}
pub trait Write {
type WriteFuture<'a>: Future<Output = Result<(), Error>>
where
Self: 'a;
fn write<'a>(self: Pin<&'a mut Self>, buf: &'a [u8]) -> Self::WriteFuture<'a>;
} }

View File

@ -2,6 +2,7 @@
mod drop_bomb; mod drop_bomb;
mod forever; mod forever;
mod mutex; mod mutex;
mod on_drop;
mod portal; mod portal;
mod signal; mod signal;
@ -11,6 +12,7 @@ mod waker;
pub use drop_bomb::*; pub use drop_bomb::*;
pub use forever::*; pub use forever::*;
pub use mutex::*; pub use mutex::*;
pub use on_drop::*;
pub use portal::*; pub use portal::*;
pub use signal::*; pub use signal::*;
pub use waker::*; pub use waker::*;

View File

@ -0,0 +1,24 @@
use core::mem;
use core::mem::MaybeUninit;
pub struct OnDrop<F: FnOnce()> {
f: MaybeUninit<F>,
}
impl<F: FnOnce()> OnDrop<F> {
pub fn new(f: F) -> Self {
Self {
f: MaybeUninit::new(f),
}
}
pub fn defuse(self) {
mem::forget(self)
}
}
impl<F: FnOnce()> Drop for OnDrop<F> {
fn drop(&mut self) {
unsafe { self.f.as_ptr().read()() }
}
}