Merge pull request #3 from timokroeger/low-power-uarte
(low power) UARTE implementation
This commit is contained in:
commit
cd56d2621a
@ -26,6 +26,7 @@ log = { version = "0.4.11", optional = true }
|
||||
cortex-m-rt = "0.6.13"
|
||||
cortex-m = { version = "0.6.4" }
|
||||
embedded-hal = { version = "0.2.4" }
|
||||
embedded-dma = { version = "0.1.2" }
|
||||
|
||||
nrf52810-pac = { version = "0.9.0", optional = true }
|
||||
nrf52811-pac = { version = "0.9.1", optional = true }
|
||||
|
@ -57,5 +57,6 @@ pub mod interrupt;
|
||||
#[cfg(feature = "52840")]
|
||||
pub mod qspi;
|
||||
pub mod rtc;
|
||||
pub mod uarte;
|
||||
|
||||
pub use cortex_m_rt::interrupt;
|
||||
|
418
embassy-nrf/src/uarte.rs
Normal file
418
embassy-nrf/src/uarte.rs
Normal file
@ -0,0 +1,418 @@
|
||||
//! Async low power UARTE.
|
||||
//!
|
||||
//! The peripheral is automatically enabled and disabled as required to save power.
|
||||
//! Lowest power consumption can only be guaranteed if the send receive futures
|
||||
//! are dropped correctly (e.g. not using `mem::forget()`).
|
||||
|
||||
use core::future::Future;
|
||||
use core::ops::Deref;
|
||||
use core::sync::atomic::{compiler_fence, Ordering};
|
||||
use core::task::{Context, Poll};
|
||||
|
||||
use embassy::util::Signal;
|
||||
use embedded_dma::{ReadBuffer, WriteBuffer};
|
||||
|
||||
use crate::fmt::{assert, *};
|
||||
#[cfg(any(feature = "52833", feature = "52840"))]
|
||||
use crate::hal::gpio::Port as GpioPort;
|
||||
use crate::hal::pac;
|
||||
use crate::hal::prelude::*;
|
||||
use crate::hal::target_constants::EASY_DMA_SIZE;
|
||||
use crate::interrupt;
|
||||
use crate::interrupt::OwnedInterrupt;
|
||||
|
||||
pub use crate::hal::uarte::Pins;
|
||||
// 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};
|
||||
|
||||
/// Interface to the UARTE peripheral
|
||||
pub struct Uarte<T>
|
||||
where
|
||||
T: Instance,
|
||||
{
|
||||
instance: T,
|
||||
irq: T::Interrupt,
|
||||
pins: Pins,
|
||||
}
|
||||
|
||||
pub struct State {
|
||||
tx_done: Signal<()>,
|
||||
rx_done: Signal<u32>,
|
||||
}
|
||||
|
||||
// TODO: Remove when https://github.com/nrf-rs/nrf-hal/pull/276 has landed
|
||||
#[cfg(any(feature = "52833", feature = "52840"))]
|
||||
fn port_bit(port: GpioPort) -> bool {
|
||||
match port {
|
||||
GpioPort::Port0 => false,
|
||||
GpioPort::Port1 => true,
|
||||
}
|
||||
}
|
||||
|
||||
impl<T> Uarte<T>
|
||||
where
|
||||
T: Instance,
|
||||
{
|
||||
/// Creates the interface to a UARTE instance.
|
||||
/// Sets the baud rate, parity and assigns the pins to the UARTE peripheral.
|
||||
///
|
||||
/// # Unsafe
|
||||
///
|
||||
/// The returned API is safe unless you use `mem::forget` (or similar safe mechanisms)
|
||||
/// on stack allocated buffers which which have been passed to [`send()`](Uarte::send)
|
||||
/// or [`receive`](Uarte::receive).
|
||||
#[allow(unused_unsafe)]
|
||||
pub unsafe fn new(
|
||||
uarte: T,
|
||||
irq: T::Interrupt,
|
||||
mut pins: Pins,
|
||||
parity: Parity,
|
||||
baudrate: Baudrate,
|
||||
) -> Self {
|
||||
assert!(uarte.enable.read().enable().is_disabled());
|
||||
|
||||
uarte.psel.rxd.write(|w| {
|
||||
let w = unsafe { w.pin().bits(pins.rxd.pin()) };
|
||||
#[cfg(any(feature = "52833", feature = "52840"))]
|
||||
let w = w.port().bit(port_bit(pins.rxd.port()));
|
||||
w.connect().connected()
|
||||
});
|
||||
|
||||
pins.txd.set_high().unwrap();
|
||||
uarte.psel.txd.write(|w| {
|
||||
let w = unsafe { w.pin().bits(pins.txd.pin()) };
|
||||
#[cfg(any(feature = "52833", feature = "52840"))]
|
||||
let w = w.port().bit(port_bit(pins.txd.port()));
|
||||
w.connect().connected()
|
||||
});
|
||||
|
||||
// Optional pins
|
||||
uarte.psel.cts.write(|w| {
|
||||
if let Some(ref pin) = pins.cts {
|
||||
let w = unsafe { w.pin().bits(pin.pin()) };
|
||||
#[cfg(any(feature = "52833", feature = "52840"))]
|
||||
let w = w.port().bit(port_bit(pin.port()));
|
||||
w.connect().connected()
|
||||
} else {
|
||||
w.connect().disconnected()
|
||||
}
|
||||
});
|
||||
|
||||
uarte.psel.rts.write(|w| {
|
||||
if let Some(ref pin) = pins.rts {
|
||||
let w = unsafe { w.pin().bits(pin.pin()) };
|
||||
#[cfg(any(feature = "52833", feature = "52840"))]
|
||||
let w = w.port().bit(port_bit(pin.port()));
|
||||
w.connect().connected()
|
||||
} else {
|
||||
w.connect().disconnected()
|
||||
}
|
||||
});
|
||||
|
||||
uarte.baudrate.write(|w| w.baudrate().variant(baudrate));
|
||||
uarte.config.write(|w| w.parity().variant(parity));
|
||||
|
||||
// Enable interrupts
|
||||
uarte.events_endtx.reset();
|
||||
uarte.events_endrx.reset();
|
||||
uarte
|
||||
.intenset
|
||||
.write(|w| w.endtx().set().txstopped().set().endrx().set().rxto().set());
|
||||
|
||||
// Register ISR
|
||||
irq.set_handler(Self::on_irq);
|
||||
irq.unpend();
|
||||
irq.enable();
|
||||
|
||||
Uarte {
|
||||
instance: uarte,
|
||||
irq,
|
||||
pins,
|
||||
}
|
||||
}
|
||||
|
||||
pub fn free(self) -> (T, T::Interrupt, Pins) {
|
||||
(self.instance, self.irq, self.pins)
|
||||
}
|
||||
|
||||
fn enable(&mut self) {
|
||||
trace!("enable");
|
||||
self.instance.enable.write(|w| w.enable().enabled());
|
||||
}
|
||||
|
||||
/// Sends serial data.
|
||||
///
|
||||
/// `tx_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.
|
||||
pub fn send<'a, B>(&'a mut self, tx_buffer: B) -> SendFuture<'a, T, B>
|
||||
where
|
||||
B: ReadBuffer<Word = u8>,
|
||||
{
|
||||
// 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());
|
||||
|
||||
self.enable();
|
||||
|
||||
SendFuture {
|
||||
uarte: self,
|
||||
buf: tx_buffer,
|
||||
}
|
||||
}
|
||||
|
||||
fn tx_started(&self) -> bool {
|
||||
self.instance.events_txstarted.read().bits() != 0
|
||||
}
|
||||
|
||||
/// Receives serial data.
|
||||
///
|
||||
/// 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.
|
||||
pub fn receive<'a, B>(&'a mut self, rx_buffer: B) -> ReceiveFuture<'a, T, B>
|
||||
where
|
||||
B: WriteBuffer<Word = u8>,
|
||||
{
|
||||
// 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());
|
||||
|
||||
self.enable();
|
||||
|
||||
ReceiveFuture {
|
||||
uarte: self,
|
||||
buf: Some(rx_buffer),
|
||||
}
|
||||
}
|
||||
|
||||
fn rx_started(&self) -> bool {
|
||||
self.instance.events_rxstarted.read().bits() != 0
|
||||
}
|
||||
|
||||
unsafe fn on_irq() {
|
||||
let uarte = &*pac::UARTE0::ptr();
|
||||
|
||||
let mut try_disable = false;
|
||||
|
||||
if uarte.events_endtx.read().bits() != 0 {
|
||||
uarte.events_endtx.reset();
|
||||
trace!("endtx");
|
||||
compiler_fence(Ordering::SeqCst);
|
||||
T::state().tx_done.signal(());
|
||||
}
|
||||
|
||||
if uarte.events_txstopped.read().bits() != 0 {
|
||||
uarte.events_txstopped.reset();
|
||||
trace!("txstopped");
|
||||
try_disable = true;
|
||||
}
|
||||
|
||||
if uarte.events_endrx.read().bits() != 0 {
|
||||
uarte.events_endrx.reset();
|
||||
trace!("endrx");
|
||||
let len = uarte.rxd.amount.read().bits();
|
||||
compiler_fence(Ordering::SeqCst);
|
||||
T::state().rx_done.signal(len);
|
||||
}
|
||||
|
||||
if uarte.events_rxto.read().bits() != 0 {
|
||||
uarte.events_rxto.reset();
|
||||
trace!("rxto");
|
||||
try_disable = true;
|
||||
}
|
||||
|
||||
// Disable the peripheral if not active.
|
||||
if try_disable
|
||||
&& uarte.events_txstarted.read().bits() == 0
|
||||
&& uarte.events_rxstarted.read().bits() == 0
|
||||
{
|
||||
trace!("disable");
|
||||
uarte.enable.write(|w| w.enable().disabled());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/// Future for the [`Uarte::send()`] method.
|
||||
pub struct SendFuture<'a, T, B>
|
||||
where
|
||||
T: Instance,
|
||||
{
|
||||
uarte: &'a Uarte<T>,
|
||||
buf: B,
|
||||
}
|
||||
|
||||
impl<'a, T, B> Drop for SendFuture<'a, T, B>
|
||||
where
|
||||
T: Instance,
|
||||
{
|
||||
fn drop(self: &mut Self) {
|
||||
if self.uarte.tx_started() {
|
||||
trace!("stoptx");
|
||||
|
||||
// Stop the transmitter to minimize the current consumption.
|
||||
self.uarte.instance.events_txstarted.reset();
|
||||
self.uarte
|
||||
.instance
|
||||
.tasks_stoptx
|
||||
.write(|w| unsafe { w.bits(1) });
|
||||
T::state().tx_done.blocking_wait();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl<'a, T, B> Future for SendFuture<'a, T, B>
|
||||
where
|
||||
T: Instance,
|
||||
B: ReadBuffer<Word = u8>,
|
||||
{
|
||||
type Output = ();
|
||||
|
||||
fn poll(self: core::pin::Pin<&mut Self>, cx: &mut Context<'_>) -> Poll<()> {
|
||||
let Self { uarte, buf } = unsafe { self.get_unchecked_mut() };
|
||||
|
||||
if !uarte.tx_started() {
|
||||
let uarte = &uarte.instance;
|
||||
|
||||
T::state().tx_done.reset();
|
||||
|
||||
let (ptr, len) = unsafe { buf.read_buffer() };
|
||||
assert!(len <= EASY_DMA_SIZE);
|
||||
// TODO: panic if buffer is not in SRAM
|
||||
|
||||
compiler_fence(Ordering::SeqCst);
|
||||
uarte.txd.ptr.write(|w| unsafe { w.ptr().bits(ptr as u32) });
|
||||
uarte
|
||||
.txd
|
||||
.maxcnt
|
||||
.write(|w| unsafe { w.maxcnt().bits(len as _) });
|
||||
|
||||
trace!("starttx");
|
||||
uarte.tasks_starttx.write(|w| unsafe { w.bits(1) });
|
||||
}
|
||||
|
||||
T::state().tx_done.poll_wait(cx)
|
||||
}
|
||||
}
|
||||
|
||||
/// Future for the [`Uarte::receive()`] method.
|
||||
pub struct ReceiveFuture<'a, T, B>
|
||||
where
|
||||
T: Instance,
|
||||
{
|
||||
uarte: &'a Uarte<T>,
|
||||
buf: Option<B>,
|
||||
}
|
||||
|
||||
impl<'a, T, B> Drop for ReceiveFuture<'a, T, B>
|
||||
where
|
||||
T: Instance,
|
||||
{
|
||||
fn drop(self: &mut Self) {
|
||||
if self.uarte.rx_started() {
|
||||
trace!("stoprx");
|
||||
|
||||
self.uarte.instance.events_rxstarted.reset();
|
||||
self.uarte
|
||||
.instance
|
||||
.tasks_stoprx
|
||||
.write(|w| unsafe { w.bits(1) });
|
||||
T::state().rx_done.blocking_wait();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl<'a, T, B> Future for ReceiveFuture<'a, T, B>
|
||||
where
|
||||
T: Instance,
|
||||
B: WriteBuffer<Word = u8>,
|
||||
{
|
||||
type Output = B;
|
||||
|
||||
fn poll(self: core::pin::Pin<&mut Self>, cx: &mut Context<'_>) -> Poll<B> {
|
||||
let Self { uarte, buf } = unsafe { self.get_unchecked_mut() };
|
||||
|
||||
if !uarte.rx_started() {
|
||||
let uarte = &uarte.instance;
|
||||
|
||||
T::state().rx_done.reset();
|
||||
|
||||
let (ptr, len) = unsafe { buf.as_mut().unwrap().write_buffer() };
|
||||
assert!(len <= EASY_DMA_SIZE);
|
||||
|
||||
compiler_fence(Ordering::SeqCst);
|
||||
uarte.rxd.ptr.write(|w| unsafe { w.ptr().bits(ptr as u32) });
|
||||
uarte
|
||||
.rxd
|
||||
.maxcnt
|
||||
.write(|w| unsafe { w.maxcnt().bits(len as _) });
|
||||
|
||||
trace!("startrx");
|
||||
uarte.tasks_startrx.write(|w| unsafe { w.bits(1) });
|
||||
}
|
||||
|
||||
T::state()
|
||||
.rx_done
|
||||
.poll_wait(cx)
|
||||
.map(|_| buf.take().unwrap())
|
||||
}
|
||||
}
|
||||
|
||||
/// Future for the [`receive()`] method.
|
||||
impl<'a, T, B> ReceiveFuture<'a, T, B>
|
||||
where
|
||||
T: Instance,
|
||||
{
|
||||
/// Stops the ongoing reception and returns the number of bytes received.
|
||||
pub async fn stop(mut self) -> (B, usize) {
|
||||
let buf = self.buf.take().unwrap();
|
||||
drop(self);
|
||||
let len = T::state().rx_done.wait().await;
|
||||
(buf, len as _)
|
||||
}
|
||||
}
|
||||
|
||||
mod private {
|
||||
pub trait Sealed {}
|
||||
}
|
||||
|
||||
pub trait Instance: Deref<Target = pac::uarte0::RegisterBlock> + Sized + private::Sealed {
|
||||
type Interrupt: OwnedInterrupt;
|
||||
|
||||
#[doc(hidden)]
|
||||
fn state() -> &'static State;
|
||||
}
|
||||
|
||||
static UARTE0_STATE: State = State {
|
||||
tx_done: Signal::new(),
|
||||
rx_done: Signal::new(),
|
||||
};
|
||||
impl private::Sealed for pac::UARTE0 {}
|
||||
impl Instance for pac::UARTE0 {
|
||||
type Interrupt = interrupt::UARTE0_UART0Interrupt;
|
||||
|
||||
fn state() -> &'static State {
|
||||
&UARTE0_STATE
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(any(feature = "52833", feature = "52840", feature = "9160"))]
|
||||
static UARTE1_STATE: State = State {
|
||||
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::UARTE1Interrupt;
|
||||
|
||||
fn state() -> &'static State {
|
||||
&UARTE1_STATE
|
||||
}
|
||||
}
|
@ -62,4 +62,13 @@ impl<T: Send> Signal<T> {
|
||||
pub fn wait(&self) -> impl Future<Output = T> + '_ {
|
||||
futures::future::poll_fn(move |cx| self.poll_wait(cx))
|
||||
}
|
||||
|
||||
/// Blocks until the signal has been received.
|
||||
///
|
||||
/// Returns immediately when [`poll_wait()`] has not been called before.
|
||||
pub fn blocking_wait(&self) {
|
||||
while cortex_m::interrupt::free(|_| {
|
||||
matches!(unsafe { &*self.state.get() }, State::Waiting(_))
|
||||
}) {}
|
||||
}
|
||||
}
|
||||
|
84
examples/src/bin/buffered_uart.rs
Normal file
84
examples/src/bin/buffered_uart.rs
Normal file
@ -0,0 +1,84 @@
|
||||
#![no_std]
|
||||
#![no_main]
|
||||
#![feature(type_alias_impl_trait)]
|
||||
|
||||
#[path = "../example_common.rs"]
|
||||
mod example_common;
|
||||
use example_common::*;
|
||||
|
||||
use cortex_m_rt::entry;
|
||||
use defmt::panic;
|
||||
use futures::pin_mut;
|
||||
use nrf52840_hal::gpio;
|
||||
|
||||
use embassy::executor::{task, Executor};
|
||||
use embassy::io::{AsyncBufRead, AsyncBufReadExt, AsyncWrite, AsyncWriteExt};
|
||||
use embassy::util::Forever;
|
||||
use embassy_nrf::buffered_uarte;
|
||||
use embassy_nrf::interrupt;
|
||||
|
||||
#[task]
|
||||
async fn run() {
|
||||
let p = unwrap!(embassy_nrf::pac::Peripherals::take());
|
||||
|
||||
let port0 = gpio::p0::Parts::new(p.P0);
|
||||
|
||||
let pins = buffered_uarte::Pins {
|
||||
rxd: port0.p0_08.into_floating_input().degrade(),
|
||||
txd: port0
|
||||
.p0_06
|
||||
.into_push_pull_output(gpio::Level::Low)
|
||||
.degrade(),
|
||||
cts: None,
|
||||
rts: None,
|
||||
};
|
||||
|
||||
let irq = interrupt::take!(UARTE0_UART0);
|
||||
let u = buffered_uarte::BufferedUarte::new(
|
||||
p.UARTE0,
|
||||
irq,
|
||||
pins,
|
||||
buffered_uarte::Parity::EXCLUDED,
|
||||
buffered_uarte::Baudrate::BAUD115200,
|
||||
);
|
||||
pin_mut!(u);
|
||||
|
||||
info!("uarte initialized!");
|
||||
|
||||
unwrap!(u.write_all(b"Hello!\r\n").await);
|
||||
info!("wrote hello in uart!");
|
||||
|
||||
// Simple demo, reading 8-char chunks and echoing them back reversed.
|
||||
loop {
|
||||
info!("reading...");
|
||||
let mut buf = [0u8; 8];
|
||||
unwrap!(u.read_exact(&mut buf).await);
|
||||
info!("read done, got {:[u8]}", buf);
|
||||
|
||||
// Reverse buf
|
||||
for i in 0..4 {
|
||||
let tmp = buf[i];
|
||||
buf[i] = buf[7 - i];
|
||||
buf[7 - i] = tmp;
|
||||
}
|
||||
|
||||
info!("writing...");
|
||||
unwrap!(u.write_all(&buf).await);
|
||||
info!("write done");
|
||||
}
|
||||
}
|
||||
|
||||
static EXECUTOR: Forever<Executor> = Forever::new();
|
||||
|
||||
#[entry]
|
||||
fn main() -> ! {
|
||||
info!("Hello World!");
|
||||
|
||||
let executor = EXECUTOR.put(Executor::new(cortex_m::asm::sev));
|
||||
unwrap!(executor.spawn(run()));
|
||||
|
||||
loop {
|
||||
executor.run();
|
||||
cortex_m::asm::wfe();
|
||||
}
|
||||
}
|
@ -8,22 +8,76 @@ use example_common::*;
|
||||
|
||||
use cortex_m_rt::entry;
|
||||
use defmt::panic;
|
||||
use futures::pin_mut;
|
||||
use embassy::executor::{task, Executor};
|
||||
use embassy::time::{Duration, Timer};
|
||||
use embassy::util::Forever;
|
||||
use embassy_nrf::{interrupt, pac, rtc, uarte};
|
||||
use futures::future::{select, Either};
|
||||
use nrf52840_hal::clocks;
|
||||
use nrf52840_hal::gpio;
|
||||
|
||||
use embassy::executor::{task, Executor};
|
||||
use embassy::io::{AsyncBufRead, AsyncBufReadExt, AsyncWrite, AsyncWriteExt};
|
||||
use embassy::util::Forever;
|
||||
use embassy_nrf::buffered_uarte;
|
||||
use embassy_nrf::interrupt;
|
||||
|
||||
#[task]
|
||||
async fn run() {
|
||||
async fn run(mut uart: uarte::Uarte<pac::UARTE0>) {
|
||||
info!("uarte initialized!");
|
||||
|
||||
// Message must be in SRAM
|
||||
let mut buf = [0; 8];
|
||||
buf.copy_from_slice(b"Hello!\r\n");
|
||||
|
||||
uart.send(&buf).await;
|
||||
info!("wrote hello in uart!");
|
||||
|
||||
info!("reading...");
|
||||
loop {
|
||||
let received = match select(
|
||||
uart.receive(&mut buf),
|
||||
Timer::after(Duration::from_millis(10)),
|
||||
)
|
||||
.await
|
||||
{
|
||||
Either::Left((buf, _)) => buf,
|
||||
Either::Right((_, read)) => {
|
||||
let (buf, n) = read.stop().await;
|
||||
&buf[..n]
|
||||
}
|
||||
};
|
||||
|
||||
if received.len() > 0 {
|
||||
info!("read done, got {:[u8]}", received);
|
||||
|
||||
// Echo back received data
|
||||
uart.send(received).await;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static RTC: Forever<rtc::RTC<pac::RTC1>> = Forever::new();
|
||||
static ALARM: Forever<rtc::Alarm<pac::RTC1>> = Forever::new();
|
||||
static EXECUTOR: Forever<Executor> = Forever::new();
|
||||
|
||||
#[entry]
|
||||
fn main() -> ! {
|
||||
info!("Hello World!");
|
||||
|
||||
let p = unwrap!(embassy_nrf::pac::Peripherals::take());
|
||||
|
||||
clocks::Clocks::new(p.CLOCK)
|
||||
.enable_ext_hfosc()
|
||||
.set_lfclk_src_external(clocks::LfOscConfiguration::NoExternalNoBypass)
|
||||
.start_lfclk();
|
||||
|
||||
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 executor = EXECUTOR.put(Executor::new_with_alarm(alarm, cortex_m::asm::sev));
|
||||
|
||||
// Init UART
|
||||
let port0 = gpio::p0::Parts::new(p.P0);
|
||||
|
||||
let pins = buffered_uarte::Pins {
|
||||
let pins = uarte::Pins {
|
||||
rxd: port0.p0_08.into_floating_input().degrade(),
|
||||
txd: port0
|
||||
.p0_06
|
||||
@ -33,49 +87,18 @@ async fn run() {
|
||||
rts: None,
|
||||
};
|
||||
|
||||
let irq = interrupt::take!(UARTE0_UART0);
|
||||
let u = buffered_uarte::BufferedUarte::new(
|
||||
p.UARTE0,
|
||||
irq,
|
||||
pins,
|
||||
buffered_uarte::Parity::EXCLUDED,
|
||||
buffered_uarte::Baudrate::BAUD115200,
|
||||
);
|
||||
pin_mut!(u);
|
||||
// NOTE(unsafe): Safe becasue we do not use `mem::forget` anywhere.
|
||||
let uart = unsafe {
|
||||
uarte::Uarte::new(
|
||||
p.UARTE0,
|
||||
interrupt::take!(UARTE0_UART0),
|
||||
pins,
|
||||
uarte::Parity::EXCLUDED,
|
||||
uarte::Baudrate::BAUD115200,
|
||||
)
|
||||
};
|
||||
|
||||
info!("uarte initialized!");
|
||||
|
||||
unwrap!(u.write_all(b"Hello!\r\n").await);
|
||||
info!("wrote hello in uart!");
|
||||
|
||||
// Simple demo, reading 8-char chunks and echoing them back reversed.
|
||||
loop {
|
||||
info!("reading...");
|
||||
let mut buf = [0u8; 8];
|
||||
unwrap!(u.read_exact(&mut buf).await);
|
||||
info!("read done, got {:[u8]}", buf);
|
||||
|
||||
// Reverse buf
|
||||
for i in 0..4 {
|
||||
let tmp = buf[i];
|
||||
buf[i] = buf[7 - i];
|
||||
buf[7 - i] = tmp;
|
||||
}
|
||||
|
||||
info!("writing...");
|
||||
unwrap!(u.write_all(&buf).await);
|
||||
info!("write done");
|
||||
}
|
||||
}
|
||||
|
||||
static EXECUTOR: Forever<Executor> = Forever::new();
|
||||
|
||||
#[entry]
|
||||
fn main() -> ! {
|
||||
info!("Hello World!");
|
||||
|
||||
let executor = EXECUTOR.put(Executor::new(cortex_m::asm::sev));
|
||||
unwrap!(executor.spawn(run()));
|
||||
unwrap!(executor.spawn(run(uart)));
|
||||
|
||||
loop {
|
||||
executor.run();
|
||||
|
Loading…
Reference in New Issue
Block a user