diff --git a/boards/rp-pico/Cargo.toml b/boards/rp-pico/Cargo.toml index e12670f..603cfd5 100644 --- a/boards/rp-pico/Cargo.toml +++ b/boards/rp-pico/Cargo.toml @@ -27,6 +27,7 @@ embedded-hal ="0.2.5" cortex-m-rtic = "0.6.0-rc.4" nb = "1.0" i2c-pio = { git = "https://github.com/ithinuel/i2c-pio-rs", rev = "df06e4ac94a5b2c985d6a9426dc4cc9be0d535c0" } +heapless = "0.7.9" [features] default = ["boot2", "rt"] diff --git a/boards/rp-pico/examples/pico_uart_irq_buffer.rs b/boards/rp-pico/examples/pico_uart_irq_buffer.rs new file mode 100644 index 0000000..c8d2a52 --- /dev/null +++ b/boards/rp-pico/examples/pico_uart_irq_buffer.rs @@ -0,0 +1,298 @@ +//! # UART IRQ TX BUffer Example +//! +//! This application demonstrates how to use the UART Driver to talk to a +//! serial connection. In this example, the IRQ owns the UART and you cannot +//! do any UART access from the main thread. You can, however, write to a +//! static queue, and have the queue contents transferred to the UART under +//! interrupt. +//! +//! It may need to be adapted to your particular board layout and/or pin +//! assignment. The pinouts assume you have a Raspberry Pi Pico or compatible: +//! +//! * GPIO 0 - UART TX (out of the RP2040) +//! * GPIO 1 - UART RX (in to the RP2040) +//! * GPIO 25 - An LED we can blink (active high) +//! +//! See the `Cargo.toml` file for Copyright and licence details. + +#![no_std] +#![no_main] + +// These are the traits we need from Embedded HAL to treat our hardware +// objects as generic embedded devices. +use embedded_hal::{digital::v2::OutputPin, serial::Write as UartWrite}; + +// We need this for the 'Delay' object to work. +use embedded_time::fixed_point::FixedPoint; + +// The writeln! trait. +use core::fmt::Write; + +// We also need this for the 'Delay' object to work. +use rp2040_hal::Clock; + +// The macro for our start-up function +use cortex_m_rt::entry; + +// Ensure we halt the program on panic (if we don't mention this crate it won't +// be linked) +use panic_halt as _; + +// Alias for our HAL crate +use rp2040_hal as hal; + +// A shorter alias for the Peripheral Access Crate, which provides low-level +// register access +use hal::pac; + +// Our interrupt macro +use pac::interrupt; + +// Some short-cuts to useful types +use core::cell::RefCell; +use cortex_m::interrupt::Mutex; +use heapless::spsc::Queue; + +/// Import the GPIO pins we use +use hal::gpio::pin::bank0::{Gpio0, Gpio1}; + +/// Alias the type for our UART pins to make things clearer. +type UartPins = ( + hal::gpio::Pin>, + hal::gpio::Pin>, +); + +/// Alias the type for our UART to make things clearer. +type Uart = hal::uart::UartPeripheral; + +/// This describes the queue we use for outbound UART data +struct UartQueue { + mutex_cell_queue: Mutex>>, + interrupt: pac::Interrupt, +} + +/// The linker will place this boot block at the start of our program image. We +// need this to help the ROM bootloader get our code up and running. +#[link_section = ".boot2"] +#[used] +pub static BOOT2: [u8; 256] = rp2040_boot2::BOOT_LOADER_W25Q080; + +/// External high-speed crystal on the Raspberry Pi Pico board is 12 MHz. Adjust +/// if your board has a different frequency +const XTAL_FREQ_HZ: u32 = 12_000_000u32; + +/// This how we transfer the UART into the Interrupt Handler +static GLOBAL_UART: Mutex>> = Mutex::new(RefCell::new(None)); + +/// This is our outbound UART queue. We write to it from the main thread, and +/// read from it in the UART IRQ. +static UART_TX_QUEUE: UartQueue = UartQueue { + mutex_cell_queue: Mutex::new(RefCell::new(Queue::new())), + interrupt: hal::pac::Interrupt::UART0_IRQ, +}; + +/// Entry point to our bare-metal application. +/// +/// The `#[entry]` macro ensures the Cortex-M start-up code calls this function +/// as soon as all global variables are initialised. +/// +/// The function configures the RP2040 peripherals, then writes to the UART in +/// an inifinite loop. +#[entry] +fn main() -> ! { + // Grab our singleton objects + let mut pac = pac::Peripherals::take().unwrap(); + let core = pac::CorePeripherals::take().unwrap(); + + // Set up the watchdog driver - needed by the clock setup code + let mut watchdog = hal::Watchdog::new(pac.WATCHDOG); + + // Configure the clocks + let clocks = hal::clocks::init_clocks_and_plls( + XTAL_FREQ_HZ, + pac.XOSC, + pac.CLOCKS, + pac.PLL_SYS, + pac.PLL_USB, + &mut pac.RESETS, + &mut watchdog, + ) + .ok() + .unwrap(); + + // Lets us wait for fixed periods of time + let mut delay = cortex_m::delay::Delay::new(core.SYST, clocks.system_clock.freq().integer()); + + // The single-cycle I/O block controls our GPIO pins + let sio = hal::Sio::new(pac.SIO); + + // Set the pins to their default state + let pins = hal::gpio::Pins::new( + pac.IO_BANK0, + pac.PADS_BANK0, + sio.gpio_bank0, + &mut pac.RESETS, + ); + + let uart_pins = ( + // UART TX (characters sent from RP2040) on pin 1 (GPIO0) + pins.gpio0.into_mode::(), + // UART RX (characters reveived by RP2040) on pin 2 (GPIO1) + pins.gpio1.into_mode::(), + ); + + // Make a UART on the given pins + let mut uart = hal::uart::UartPeripheral::new(pac.UART0, uart_pins, &mut pac.RESETS) + .enable( + hal::uart::common_configs::_9600_8_N_1, + clocks.peripheral_clock.into(), + ) + .unwrap(); + + // Tell the UART to raise its interrupt line on the NVIC when the TX FIFO + // has space in it. + uart.enable_tx_interrupt(); + + // Now we give away the entire UART peripheral, via the variable + // `GLOBAL_UART`. We can no longer access the UART from this main thread. + cortex_m::interrupt::free(|cs| { + GLOBAL_UART.borrow(cs).replace(Some(uart)); + }); + + // But we can blink an LED. + let mut led_pin = pins.gpio25.into_push_pull_output(); + + loop { + // Light the LED whilst the main thread is in the transmit routine. It + // shouldn't be on very long, but it will be on whilst we get enough + // data /out/ of the queue and over the UART for this remainder of + // this string to fit. + led_pin.set_high().unwrap(); + // Note we can only write to &UART_TX_QUEUE, because it's not mutable and + // `core::fmt::Write` takes mutable references. + writeln!( + &UART_TX_QUEUE, + "Hello, this was sent under interrupt! It's quite a \ + long message, designed not to fit in either the \ + hardware FIFO or the software queue." + ) + .unwrap(); + led_pin.set_low().unwrap(); + // Wait for a second - the UART TX IRQ will transmit the remainder of our queue contents in the background. + delay.delay_ms(1000); + } +} + +impl UartQueue { + /// Try and get some data out of the UART Queue. Returns None if queue empty. + fn read_byte(&self) -> Option { + cortex_m::interrupt::free(|cs| { + let cell_queue = self.mutex_cell_queue.borrow(cs); + let mut queue = cell_queue.borrow_mut(); + queue.dequeue() + }) + } + + /// Peek at the next byte in the queue without removing it. + fn peek_byte(&self) -> Option { + cortex_m::interrupt::free(|cs| { + let cell_queue = self.mutex_cell_queue.borrow(cs); + let queue = cell_queue.borrow_mut(); + queue.peek().cloned() + }) + } + + /// Write some data to the queue, spinning until it all fits. + fn write_bytes_blocking(&self, data: &[u8]) { + // Go through all the bytes we need to write. + for byte in data.iter() { + // Keep trying until there is space in the queue. But release the + // mutex between each attempt, otherwise the IRQ will never run + // and we will never have space! + let mut written = false; + while !written { + // Grab the mutex, by turning interrupts off. NOTE: This + // doesn't work if you are using Core 1 as we only turn + // interrupts off on one core. + cortex_m::interrupt::free(|cs| { + // Grab the mutex contents. + let cell_queue = self.mutex_cell_queue.borrow(cs); + // Grab mutable access to the queue. This can't fail + // because there are no interrupts running. + let mut queue = cell_queue.borrow_mut(); + // Try and put the byte in the queue. + if queue.enqueue(*byte).is_ok() { + // It worked! We must have had space. + if !pac::NVIC::is_enabled(self.interrupt) { + unsafe { + // Now enable the UART interrupt in the *Nested + // Vectored Interrupt Controller*, which is part + // of the Cortex-M0+ core. If the FIFO has space, + // the interrupt will run as soon as we're out of + // the closure. + pac::NVIC::unmask(self.interrupt); + // We also have to kick the IRQ in case the FIFO + // was already below the threshold level. + pac::NVIC::pend(self.interrupt); + } + } + written = true; + } + }); + } + } + } +} + +impl core::fmt::Write for &UartQueue { + /// This function allows us to `writeln!` on our global static UART queue. + /// Note we have an impl for &UartQueue, because our global static queue + /// is not mutable and `core::fmt::Write` takes mutable references. + fn write_str(&mut self, data: &str) -> core::fmt::Result { + self.write_bytes_blocking(data.as_bytes()); + Ok(()) + } +} + +#[interrupt] +fn UART0_IRQ() { + // This variable is special. It gets mangled by the `#[interrupt]` macro + // into something that we can access without the `unsafe` keyword. It can + // do this because this function cannot be called re-entrantly. We know + // this because the function's 'real' name is unknown, and hence it cannot + // be called from the main thread. We also know that the NVIC will not + // re-entrantly call an interrupt. + static mut UART: Option> = + None; + + // This is one-time lazy initialisation. We steal the variable given to us + // via `GLOBAL_UART`. + if UART.is_none() { + cortex_m::interrupt::free(|cs| { + *UART = GLOBAL_UART.borrow(cs).take(); + }); + } + + // Check if we have a UART to work with + if let Some(uart) = UART { + // Check if we have data to transmit + while let Some(byte) = UART_TX_QUEUE.peek_byte() { + if uart.write(byte).is_ok() { + // The UART took it, so pop it off the queue. + let _ = UART_TX_QUEUE.read_byte(); + } else { + break; + } + } + + if UART_TX_QUEUE.peek_byte().is_none() { + pac::NVIC::mask(hal::pac::Interrupt::UART0_IRQ); + } + } + + // Set an event to ensure the main thread always wakes up, even if it's in + // the process of going to sleep. + cortex_m::asm::sev(); +} + +// End of file diff --git a/boards/rp-pico/examples/pico_uart_irq_echo.rs b/boards/rp-pico/examples/pico_uart_irq_echo.rs new file mode 100644 index 0000000..c974696 --- /dev/null +++ b/boards/rp-pico/examples/pico_uart_irq_echo.rs @@ -0,0 +1,206 @@ +//! # UART IRQ Echo Example +//! +//! This application demonstrates how to use the UART Driver to talk to a serial +//! connection. In this example, the IRQ owns the UART and you cannot do any UART +//! access from the main thread. +//! +//! It may need to be adapted to your particular board layout and/or pin +//! assignment. The pinouts assume you have a Raspberry Pi Pico or compatible: +//! +//! * GPIO 0 - UART TX (out of the RP2040) +//! * GPIO 1 - UART RX (in to the RP2040) +//! * GPIO 25 - An LED we can blink (active high) +//! +//! See the `Cargo.toml` file for Copyright and licence details. + +#![no_std] +#![no_main] + +// These are the traits we need from Embedded HAL to treat our hardware +// objects as generic embedded devices. +use embedded_hal::{ + digital::v2::OutputPin, + serial::{Read, Write}, +}; + +// We need this for the 'Delay' object to work. +use embedded_time::fixed_point::FixedPoint; + +// We also need this for the 'Delay' object to work. +use rp2040_hal::Clock; + +// The macro for our start-up function +use cortex_m_rt::entry; + +// Ensure we halt the program on panic (if we don't mention this crate it won't +// be linked) +use panic_halt as _; + +// Alias for our HAL crate +use rp2040_hal as hal; + +// A shorter alias for the Peripheral Access Crate, which provides low-level +// register access +use hal::pac; + +// Our interrupt macro +use hal::pac::interrupt; + +// Some short-cuts to useful types +use core::cell::RefCell; +use cortex_m::interrupt::Mutex; + +/// Import the GPIO pins we use +use hal::gpio::pin::bank0::{Gpio0, Gpio1}; + +/// Alias the type for our UART pins to make things clearer. +type UartPins = ( + hal::gpio::Pin>, + hal::gpio::Pin>, +); + +/// Alias the type for our UART to make things clearer. +type Uart = hal::uart::UartPeripheral; + +/// The linker will place this boot block at the start of our program image. We +// need this to help the ROM bootloader get our code up and running. +#[link_section = ".boot2"] +#[used] +pub static BOOT2: [u8; 256] = rp2040_boot2::BOOT_LOADER_W25Q080; + +/// External high-speed crystal on the Raspberry Pi Pico board is 12 MHz. Adjust +/// if your board has a different frequency +const XTAL_FREQ_HZ: u32 = 12_000_000u32; + +/// This how we transfer the UART into the Interrupt Handler +static GLOBAL_UART: Mutex>> = Mutex::new(RefCell::new(None)); + +/// Entry point to our bare-metal application. +/// +/// The `#[entry]` macro ensures the Cortex-M start-up code calls this function +/// as soon as all global variables are initialised. +/// +/// The function configures the RP2040 peripherals, then writes to the UART in +/// an inifinite loop. +#[entry] +fn main() -> ! { + // Grab our singleton objects + let mut pac = pac::Peripherals::take().unwrap(); + let core = pac::CorePeripherals::take().unwrap(); + + // Set up the watchdog driver - needed by the clock setup code + let mut watchdog = hal::Watchdog::new(pac.WATCHDOG); + + // Configure the clocks + let clocks = hal::clocks::init_clocks_and_plls( + XTAL_FREQ_HZ, + pac.XOSC, + pac.CLOCKS, + pac.PLL_SYS, + pac.PLL_USB, + &mut pac.RESETS, + &mut watchdog, + ) + .ok() + .unwrap(); + + // Lets us wait for fixed periods of time + let mut delay = cortex_m::delay::Delay::new(core.SYST, clocks.system_clock.freq().integer()); + + // The single-cycle I/O block controls our GPIO pins + let sio = hal::Sio::new(pac.SIO); + + // Set the pins to their default state + let pins = hal::gpio::Pins::new( + pac.IO_BANK0, + pac.PADS_BANK0, + sio.gpio_bank0, + &mut pac.RESETS, + ); + + let uart_pins = ( + // UART TX (characters sent from RP2040) on pin 1 (GPIO0) + pins.gpio0.into_mode::(), + // UART RX (characters reveived by RP2040) on pin 2 (GPIO1) + pins.gpio1.into_mode::(), + ); + + // Make a UART on the given pins + let mut uart = hal::uart::UartPeripheral::new(pac.UART0, uart_pins, &mut pac.RESETS) + .enable( + hal::uart::common_configs::_9600_8_N_1, + clocks.peripheral_clock.into(), + ) + .unwrap(); + + unsafe { + // Enable the UART interrupt in the *Nested Vectored Interrupt + // Controller*, which is part of the Cortex-M0+ core. + pac::NVIC::unmask(hal::pac::Interrupt::UART0_IRQ); + } + + // Tell the UART to raise its interrupt line on the NVIC when the RX FIFO + // has data in it. + uart.enable_rx_interrupt(); + + // Write something to the UART on start-up so we can check the output pin + // is wired correctly. + uart.write_full_blocking(b"uart_interrupt example started...\n"); + + // Now we give away the entire UART peripheral, via the variable + // `GLOBAL_UART`. We can no longer access the UART from this main thread. + cortex_m::interrupt::free(|cs| { + GLOBAL_UART.borrow(cs).replace(Some(uart)); + }); + + // But we can blink an LED. + let mut led_pin = pins.gpio25.into_push_pull_output(); + + loop { + // The normal *Wait For Interrupts* (WFI) has a race-hazard - the + // interrupt could occur between the CPU checking for interrupts and + // the CPU going to sleep. We wait for events (and interrupts), and + // then we set an event in every interrupt handler. This ensures we + // always wake up correctly. + cortex_m::asm::wfe(); + // Light the LED to indicate we saw an interrupt. + led_pin.set_high().unwrap(); + delay.delay_ms(100); + led_pin.set_low().unwrap(); + } +} + +#[interrupt] +fn UART0_IRQ() { + // This variable is special. It gets mangled by the `#[interrupt]` macro + // into something that we can access without the `unsafe` keyword. It can + // do this because this function cannot be called re-entrantly. We know + // this because the function's 'real' name is unknown, and hence it cannot + // be called from the main thread. We also know that the NVIC will not + // re-entrantly call an interrupt. + static mut UART: Option> = + None; + + // This is one-time lazy initialisation. We steal the variable given to us + // via `GLOBAL_UART`. + if UART.is_none() { + cortex_m::interrupt::free(|cs| { + *UART = GLOBAL_UART.borrow(cs).take(); + }); + } + + // Check if we have a UART to work with + if let Some(uart) = UART { + // Echo the input back to the output until the FIFO is empty. Reading + // from the UART should also clear the UART interrupt flag. + while let Ok(byte) = uart.read() { + let _ = uart.write(byte); + } + } + + // Set an event to ensure the main thread always wakes up, even if it's in + // the process of going to sleep. + cortex_m::asm::sev(); +} + +// End of file diff --git a/rp2040-hal/src/uart/peripheral.rs b/rp2040-hal/src/uart/peripheral.rs index 0cc18df..67e474a 100644 --- a/rp2040-hal/src/uart/peripheral.rs +++ b/rp2040-hal/src/uart/peripheral.rs @@ -1,36 +1,7 @@ -//! Universal Asynchronous Receiver Transmitter (UART) +//! Universal Asynchronous Receiver Transmitter - Bi-directional Peripheral Code //! -//! See [Chapter 4 Section 2](https://datasheets.raspberrypi.org/rp2040/rp2040_datasheet.pdf) of the datasheet for more details -//! -//! ## Usage -//! -//! See [examples/uart.rs](https://github.com/rp-rs/rp-hal/tree/main/rp2040-hal/examples/uart.rs) for a more complete example -//! ```no_run -//! use rp2040_hal::{clocks::init_clocks_and_plls, gpio::{Pins, FunctionUart}, pac, Sio, uart::{self, UartPeripheral}, watchdog::Watchdog}; -//! -//! const XOSC_CRYSTAL_FREQ: u32 = 12_000_000; // Typically found in BSP crates -//! -//! let mut peripherals = pac::Peripherals::take().unwrap(); -//! let sio = Sio::new(peripherals.SIO); -//! let pins = Pins::new(peripherals.IO_BANK0, peripherals.PADS_BANK0, sio.gpio_bank0, &mut peripherals.RESETS); -//! let mut watchdog = Watchdog::new(peripherals.WATCHDOG); -//! let mut clocks = init_clocks_and_plls(XOSC_CRYSTAL_FREQ, peripherals.XOSC, peripherals.CLOCKS, peripherals.PLL_SYS, peripherals.PLL_USB, &mut peripherals.RESETS, &mut watchdog).ok().unwrap(); -//! -//! // Set up UART on GP0 and GP1 (Pico pins 1 and 2) -//! let pins = ( -//! pins.gpio0.into_mode::(), -//! pins.gpio1.into_mode::(), -//! ); -//! // Need to perform clock init before using UART or it will freeze. -//! let uart = UartPeripheral::new(peripherals.UART0, pins, &mut peripherals.RESETS) -//! .enable( -//! uart::common_configs::_9600_8_N_1, -//! clocks.peripheral_clock.into(), -//! ) -//! .unwrap(); -//! -//! uart.write_full_blocking(b"Hello World!\r\n"); -//! ``` +//! This module brings together `uart::reader` and `uart::writer` to give a +//! UartPeripheral object that can both read and write. use super::*; use crate::pac::uart0::uartlcr_h::W as UART_LCR_H_Writer; @@ -97,6 +68,7 @@ impl> UartPeripheral { let effective_baudrate = configure_baudrate(&mut device, &config.baudrate, &frequency)?; device.uartlcr_h.write(|w| { + // FIFOs are enabled w.fen().set_bit(); set_format(w, &config.data_bits, &config.stop_bits, &config.parity); w @@ -145,6 +117,40 @@ impl> UartPeripheral { self.transition(Disabled) } + /// Enables the Receive Interrupt. + /// + /// The relevant UARTx IRQ will fire when there is data in the receive register. + pub fn enable_rx_interrupt(&mut self) { + super::reader::enable_rx_interrupt(&self.device) + } + + /// Enables the Transmit Interrupt. + /// + /// The relevant UARTx IRQ will fire when there is space in the transmit FIFO. + pub fn enable_tx_interrupt(&mut self) { + super::writer::enable_tx_interrupt(&self.device) + } + + /// Disables the Receive Interrupt. + pub fn disable_rx_interrupt(&mut self) { + super::reader::disable_rx_interrupt(&self.device) + } + + /// Disables the Transmit Interrupt. + pub fn disable_tx_interrupt(&mut self) { + super::writer::disable_tx_interrupt(&self.device) + } + + /// Is there space in the UART TX FIFO for new data to be written? + pub fn uart_is_writable(&self) -> bool { + super::writer::uart_is_writable(&self.device) + } + + /// Is there data in the UART RX FIFO ready to be read? + pub fn uart_is_readable(&self) -> bool { + super::reader::is_readable(&self.device) + } + /// Writes bytes to the UART. /// This function writes as long as it can. As soon that the FIFO is full, if : /// - 0 bytes were written, a WouldBlock Error is returned diff --git a/rp2040-hal/src/uart/reader.rs b/rp2040-hal/src/uart/reader.rs index bb0f478..c8f03f3 100644 --- a/rp2040-hal/src/uart/reader.rs +++ b/rp2040-hal/src/uart/reader.rs @@ -1,4 +1,10 @@ +//! Universal Asynchronous Receiver Transmitter - Receiver Code +//! +//! This module is for receiving data with a UART. + use super::{UartConfig, UartDevice, ValidUartPinout}; +use rp2040_pac::uart0::RegisterBlock; + use embedded_hal::serial::Read; use embedded_time::rate::Baud; use nb::Error::*; @@ -47,6 +53,43 @@ pub(crate) fn is_readable(device: &D) -> bool { device.uartfr.read().rxfe().bit_is_clear() } +/// Enables the Receive Interrupt. +/// +/// The relevant UARTx IRQ will fire when there is data in the receive register. +pub(crate) fn enable_rx_interrupt(rb: &RegisterBlock) { + // Access the UART FIFO Level Select. We set the RX FIFO trip level + // to be half-full. + + // 2 means '>= 1/2 full'. + rb.uartifls.modify(|_r, w| unsafe { w.rxiflsel().bits(2) }); + + // Access the UART Interrupt Mask Set/Clear register. Setting a bit + // high enables the interrupt. + + // We set the RX interrupt, and the RX Timeout interrupt. This means + // we will get an interrupt when the RX FIFO level is triggered, or + // when the RX FIFO is non-empty, but 32-bit periods have passed with + // no further data. This means we don't have to interrupt on every + // single byte, but can make use of the hardware FIFO. + rb.uartimsc.modify(|_r, w| { + w.rxim().set_bit(); + w.rtim().set_bit(); + w + }); +} + +/// Disables the Receive Interrupt. +pub(crate) fn disable_rx_interrupt(rb: &RegisterBlock) { + // Access the UART Interrupt Mask Set/Clear register. Setting a bit + // low disables the interrupt. + + rb.uartimsc.modify(|_r, w| { + w.rxim().clear_bit(); + w.rtim().clear_bit(); + w + }); +} + pub(crate) fn read_raw<'b, D: UartDevice>( device: &D, buffer: &'b mut [u8], @@ -143,6 +186,18 @@ impl> Reader { pub fn read_full_blocking(&self, buffer: &mut [u8]) -> Result<(), ReadErrorType> { read_full_blocking(&self.device, buffer) } + + /// Enables the Receive Interrupt. + /// + /// The relevant UARTx IRQ will fire when there is data in the receive register. + pub fn enable_rx_interrupt(&mut self) { + enable_rx_interrupt(&self.device) + } + + /// Disables the Receive Interrupt. + pub fn disable_rx_interrupt(&mut self) { + disable_rx_interrupt(&self.device) + } } impl> Read for Reader { diff --git a/rp2040-hal/src/uart/writer.rs b/rp2040-hal/src/uart/writer.rs index 3944ed0..1b27c27 100644 --- a/rp2040-hal/src/uart/writer.rs +++ b/rp2040-hal/src/uart/writer.rs @@ -1,3 +1,7 @@ +//! Universal Asynchronous Receiver Transmitter - Transmitter Code +//! +//! This module is for transmitting data with a UART. + use super::{UartDevice, ValidUartPinout}; use core::fmt; use core::{convert::Infallible, marker::PhantomData}; @@ -8,6 +12,8 @@ use rp2040_pac::uart0::RegisterBlock; #[cfg(feature = "eh1_0_alpha")] use eh1_0_alpha::serial::nb as eh1; +/// Returns `Err(WouldBlock)` if the UART TX FIFO still has data in it or +/// `Ok(())` if the FIFO is empty. pub(crate) fn transmit_flushed(rb: &RegisterBlock) -> nb::Result<(), Infallible> { if rb.uartfr.read().txfe().bit_is_set() { Ok(()) @@ -16,10 +22,19 @@ pub(crate) fn transmit_flushed(rb: &RegisterBlock) -> nb::Result<(), Infallible> } } -fn uart_is_writable(rb: &RegisterBlock) -> bool { +/// Returns `true` if the TX FIFO has space, or false if it is full +pub(crate) fn uart_is_writable(rb: &RegisterBlock) -> bool { rb.uartfr.read().txff().bit_is_clear() } +/// Writes bytes to the UART. +/// +/// This function writes as long as it can. As soon that the FIFO is full, +/// if: +/// - 0 bytes were written, a WouldBlock Error is returned +/// - some bytes were written, it is deemed to be a success +/// +/// Upon success, the remaining (unwritten) slice is returned. pub(crate) fn write_raw<'d>( rb: &RegisterBlock, data: &'d [u8], @@ -45,6 +60,9 @@ pub(crate) fn write_raw<'d>( Ok(&data[bytes_written..]) } +/// Writes bytes to the UART. +/// +/// This function blocks until the full buffer has been sent. pub(crate) fn write_full_blocking(rb: &RegisterBlock, data: &[u8]) { let mut temp = data; @@ -57,6 +75,40 @@ pub(crate) fn write_full_blocking(rb: &RegisterBlock, data: &[u8]) { } } +/// Enables the Transmit Interrupt. +/// +/// The relevant UARTx IRQ will fire when there is space in the transmit FIFO. +pub(crate) fn enable_tx_interrupt(rb: &RegisterBlock) { + // Access the UART FIFO Level Select. We set the TX FIFO trip level + // to be when it's half-empty.. + + // 2 means '<= 1/2 full'. + rb.uartifls.modify(|_r, w| unsafe { w.txiflsel().bits(2) }); + + // Access the UART Interrupt Mask Set/Clear register. Setting a bit + // high enables the interrupt. + + // We set the TX interrupt. This means we will get an interrupt when + // the TX FIFO level is triggered. This means we don't have to + // interrupt on every single byte, but can make use of the hardware + // FIFO. + rb.uartimsc.modify(|_r, w| { + w.txim().set_bit(); + w + }); +} + +/// Disables the Transmit Interrupt. +pub(crate) fn disable_tx_interrupt(rb: &RegisterBlock) { + // Access the UART Interrupt Mask Set/Clear register. Setting a bit + // low disables the interrupt. + + rb.uartimsc.modify(|_r, w| { + w.txim().clear_bit(); + w + }); +} + /// Half of an [`UartPeripheral`] that is only capable of writing. Obtained by calling [`UartPeripheral::split()`] /// /// [`UartPeripheral`]: struct.UartPeripheral.html @@ -69,18 +121,34 @@ pub struct Writer> { impl> Writer { /// Writes bytes to the UART. - /// This function writes as long as it can. As soon that the FIFO is full, if : + /// + /// This function writes as long as it can. As soon that the FIFO is full, + /// if: /// - 0 bytes were written, a WouldBlock Error is returned /// - some bytes were written, it is deemed to be a success - /// Upon success, the remaining slice is returned. + /// + /// Upon success, the remaining (unwritten) slice is returned. pub fn write_raw<'d>(&self, data: &'d [u8]) -> nb::Result<&'d [u8], Infallible> { write_raw(self.device, data) } /// Writes bytes to the UART. + /// /// This function blocks until the full buffer has been sent. pub fn write_full_blocking(&self, data: &[u8]) { - super::writer::write_full_blocking(self.device, data); + write_full_blocking(self.device, data); + } + + /// Enables the Transmit Interrupt. + /// + /// The relevant UARTx IRQ will fire when there is space in the transmit FIFO. + pub fn enable_tx_interrupt(&mut self) { + enable_tx_interrupt(self.device) + } + + /// Disables the Transmit Interrupt. + pub fn disable_tx_interrupt(&mut self) { + disable_tx_interrupt(self.device) } } @@ -96,7 +164,7 @@ impl> Write for Writer { } fn flush(&mut self) -> nb::Result<(), Self::Error> { - super::writer::transmit_flushed(self.device) + transmit_flushed(self.device) } } @@ -115,7 +183,7 @@ impl> eh1::Write for Writer { fn flush(&mut self) -> nb::Result<(), Self::Error> { transmit_flushed(&self.device).map_err(|e| match e { WouldBlock => WouldBlock, - Other(v) => match v {}, + Other(_v) => {} }) } }