From a60d92cfbbacc909ba781802cad04fe00e849026 Mon Sep 17 00:00:00 2001 From: Michael van Niekerk Date: Mon, 24 Jul 2023 22:20:00 +0200 Subject: [PATCH 1/6] Tx and Rx setup --- examples/rp/.idea/.gitignore | 8 + examples/rp/.idea/modules.xml | 8 + examples/rp/.idea/rp.iml | 12 ++ examples/rp/.idea/vcs.xml | 6 + examples/rp/src/bin/pio_uart.rs | 262 ++++++++++++++++++++++++++++++++ 5 files changed, 296 insertions(+) create mode 100644 examples/rp/.idea/.gitignore create mode 100644 examples/rp/.idea/modules.xml create mode 100644 examples/rp/.idea/rp.iml create mode 100644 examples/rp/.idea/vcs.xml create mode 100644 examples/rp/src/bin/pio_uart.rs diff --git a/examples/rp/.idea/.gitignore b/examples/rp/.idea/.gitignore new file mode 100644 index 00000000..13566b81 --- /dev/null +++ b/examples/rp/.idea/.gitignore @@ -0,0 +1,8 @@ +# Default ignored files +/shelf/ +/workspace.xml +# Editor-based HTTP Client requests +/httpRequests/ +# Datasource local storage ignored files +/dataSources/ +/dataSources.local.xml diff --git a/examples/rp/.idea/modules.xml b/examples/rp/.idea/modules.xml new file mode 100644 index 00000000..06ff4b23 --- /dev/null +++ b/examples/rp/.idea/modules.xml @@ -0,0 +1,8 @@ + + + + + + + + \ No newline at end of file diff --git a/examples/rp/.idea/rp.iml b/examples/rp/.idea/rp.iml new file mode 100644 index 00000000..9b4cf845 --- /dev/null +++ b/examples/rp/.idea/rp.iml @@ -0,0 +1,12 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/examples/rp/.idea/vcs.xml b/examples/rp/.idea/vcs.xml new file mode 100644 index 00000000..b2bdec2d --- /dev/null +++ b/examples/rp/.idea/vcs.xml @@ -0,0 +1,6 @@ + + + + + + \ No newline at end of file diff --git a/examples/rp/src/bin/pio_uart.rs b/examples/rp/src/bin/pio_uart.rs new file mode 100644 index 00000000..14d05f4d --- /dev/null +++ b/examples/rp/src/bin/pio_uart.rs @@ -0,0 +1,262 @@ +//! This example shows how to use USB (Universal Serial Bus) in the RP2040 chip. +//! +//! This creates a USB serial port that echos. + +#![no_std] +#![no_main] +#![feature(type_alias_impl_trait)] + +use defmt::{info, panic}; +use embassy_executor::Spawner; +use embassy_futures::join::join; +use embassy_rp::bind_interrupts; +use embassy_rp::peripherals::{PIO0, USB}; +use embassy_rp::usb::{Driver, Instance, InterruptHandler}; +use embassy_usb::class::cdc_acm::{CdcAcmClass, State}; +use embassy_usb::driver::EndpointError; +use embassy_usb::{Builder, Config}; +use embassy_rp::pio::{InterruptHandler as PioInterruptHandler}; +use {defmt_rtt as _, panic_probe as _}; + +bind_interrupts!(struct UsbIrqs { + USBCTRL_IRQ => InterruptHandler; +}); + +bind_interrupts!(struct PioIrqs { + PIO0_IRQ_0 => PioInterruptHandler; +}); + +#[embassy_executor::main] +async fn main(_spawner: Spawner) { + info!("Hello there!"); + + let p = embassy_rp::init(Default::default()); + + // Create the driver, from the HAL. + let driver = Driver::new(p.USB, UsbIrqs); + + // Create embassy-usb Config + let mut config = Config::new(0xc0de, 0xcafe); + config.manufacturer = Some("Embassy"); + config.product = Some("PIO UART example"); + config.serial_number = Some("12345678"); + config.max_power = 100; + config.max_packet_size_0 = 64; + + // Required for windows compatibility. + // https://developer.nordicsemi.com/nRF_Connect_SDK/doc/1.9.1/kconfig/CONFIG_CDC_ACM_IAD.html#help + config.device_class = 0xEF; + config.device_sub_class = 0x02; + config.device_protocol = 0x01; + config.composite_with_iads = true; + + // Create embassy-usb DeviceBuilder using the driver and config. + // It needs some buffers for building the descriptors. + let mut device_descriptor = [0; 256]; + let mut config_descriptor = [0; 256]; + let mut bos_descriptor = [0; 256]; + let mut control_buf = [0; 64]; + + let mut state = State::new(); + + let mut builder = Builder::new( + driver, + config, + &mut device_descriptor, + &mut config_descriptor, + &mut bos_descriptor, + &mut control_buf, + ); + + // Create classes on the builder. + let mut class = CdcAcmClass::new(&mut builder, &mut state, 64); + + // Build the builder. + let mut usb = builder.build(); + + // Run the USB device. + let usb_fut = usb.run(); + + // Do stuff with the class! + let echo_fut = async { + loop { + class.wait_connection().await; + info!("Connected"); + let _ = echo(&mut class).await; + info!("Disconnected"); + } + }; + + // Run everything concurrently. + // If we had made everything `'static` above instead, we could do this using separate tasks instead. + join(usb_fut, echo_fut).await; +} + +struct Disconnected {} + +impl From for Disconnected { + fn from(val: EndpointError) -> Self { + match val { + EndpointError::BufferOverflow => panic!("Buffer overflow"), + EndpointError::Disabled => Disconnected {}, + } + } +} + +async fn echo<'d, T: Instance + 'd>(class: &mut CdcAcmClass<'d, Driver<'d, T>>) -> Result<(), Disconnected> { + let mut buf = [0; 64]; + loop { + let n = class.read_packet(&mut buf).await?; + let data = &buf[..n]; + info!("data: {:x}", data); + class.write_packet(data).await?; + } +} + +mod uart { + use embassy_rp::peripherals::PIO0; + use embassy_rp::pio::{Common, Pio, PioPin, StateMachine}; + use embassy_rp::Peripheral; + + use crate::PioIrqs; + + pub struct PioUart<'a> { + baud: u64, + pio: Common<'a, PIO0>, + sm0: StateMachine<'a, PIO0, 0>, + sm1: StateMachine<'a, PIO0, 1>, + } + + impl<'a> PioUart<'a> { + pub async fn new( + baud: u64, + pio: impl Peripheral

+ 'a, + tx_pin: impl PioPin, + rx_pin: impl PioPin, + ) -> PioUart<'a> { + let Pio { + mut common, + mut sm0, + mut sm1, + .. + } = Pio::new(pio, PioIrqs); + + crate::uart_tx::setup_uart_tx_on_sm0(&mut common, &mut sm0, tx_pin, baud); + crate::uart_rx::setup_uart_rx_on_sm1(&mut common, &mut sm1, rx_pin, baud); + + PioUart { + baud, + pio: common, + sm0, + sm1, + } + } + } +} + +mod uart_tx { + use embassy_rp::gpio::Level; + use embassy_rp::peripherals::PIO0; + use embassy_rp::pio::{Common, Config, Direction, FifoJoin, PioPin, ShiftDirection, StateMachine}; + use embassy_rp::relocate::RelocatedProgram; + use fixed::traits::ToFixed; + use fixed_macro::types::U56F8; + + pub fn setup_uart_tx_on_sm0<'a>( + common: &mut Common<'a, PIO0>, + sm_tx: &mut StateMachine<'a, PIO0, 0>, + tx_pin: impl PioPin, + baud: u64, + ) { + let prg = pio_proc::pio_asm!( + r#" + ;.program uart_tx + .side_set 1 opt + + ; An 8n1 UART transmit program. + ; OUT pin 0 and side-set pin 0 are both mapped to UART TX pin. + + pull side 1 [7] ; Assert stop bit, or stall with line in idle state + set x, 7 side 0 [7] ; Preload bit counter, assert start bit for 8 clocks + bitloop: ; This loop will run 8 times (8n1 UART) + out pins, 1 ; Shift 1 bit from OSR to the first OUT pin + jmp x-- bitloop [6] ; Each loop iteration is 8 cycles. + "# + ); + let tx_pin = common.make_pio_pin(tx_pin); + sm_tx.set_pins(Level::High, &[&tx_pin]); + sm_tx.set_pin_dirs(Direction::Out, &[&tx_pin]); + + let relocated = RelocatedProgram::new(&prg.program); + let mut cfg = Config::default(); + + cfg.use_program(&common.load_program(&relocated), &[&tx_pin]); + cfg.clock_divider = (U56F8!(125_000_000) / (8 * baud)).to_fixed(); + cfg.shift_out.auto_fill = false; + cfg.shift_out.direction = ShiftDirection::Right; + cfg.fifo_join = FifoJoin::TxOnly; + cfg.set_out_pins(&[&tx_pin]); + cfg.set_set_pins(&[&tx_pin]); + sm_tx.set_config(&cfg); + sm_tx.set_enable(true) + } +} + +mod uart_rx { + use embassy_rp::gpio::Level; + use embassy_rp::peripherals::PIO0; + use embassy_rp::pio::{Common, Config, Direction, FifoJoin, PioPin, ShiftDirection, StateMachine}; + use embassy_rp::relocate::RelocatedProgram; + use fixed::traits::ToFixed; + use fixed_macro::types::U56F8; + + pub fn setup_uart_rx_on_sm1<'a>( + common: &mut Common<'a, PIO0>, + sm_rx: &mut StateMachine<'a, PIO0, 1>, + rx_pin: impl PioPin, + baud: u64, + ) { + let prg = pio_proc::pio_asm!( + r#" + ;.program uart_rx + + ; Slightly more fleshed-out 8n1 UART receiver which handles framing errors and + ; break conditions more gracefully. + ; IN pin 0 and JMP pin are both mapped to the GPIO used as UART RX. + + start: + wait 0 pin 0 ; Stall until start bit is asserted + set x, 7 [10] ; Preload bit counter, then delay until halfway through + bitloop: ; the first data bit (12 cycles incl wait, set). + in pins, 1 ; Shift data bit into ISR + jmp x-- bitloop [6] ; Loop 8 times, each loop iteration is 8 cycles + jmp pin good_stop ; Check stop bit (should be high) + + irq 4 rel ; Either a framing error or a break. Set a sticky flag, + wait 1 pin 0 ; and wait for line to return to idle state. + jmp start ; Don't push data if we didn't see good framing. + + good_stop: ; No delay before returning to start; a little slack is + push ; important in case the TX clock is slightly too fast. + "# + ); + + let rx_pin = common.make_pio_pin(rx_pin); + sm_rx.set_pins(Level::High, &[&rx_pin]); + sm_rx.set_pin_dirs(Direction::In, &[&rx_pin]); + + let relocated = RelocatedProgram::new(&prg.program); + let mut cfg = Config::default(); + + cfg.use_program(&common.load_program(&relocated), &[&rx_pin]); + cfg.clock_divider = (U56F8!(125_000_000) / (8 * baud)).to_fixed(); + cfg.shift_out.auto_fill = false; + cfg.shift_out.direction = ShiftDirection::Right; + cfg.fifo_join = FifoJoin::RxOnly; + cfg.set_in_pins(&[&rx_pin]); + cfg.set_jmp_pin(&rx_pin); + // cfg.set_set_pins(&[&rx_pin]); + sm_rx.set_config(&cfg); + sm_rx.set_enable(true) + } +} From e947aa01533b7fd41133678ed8444a16c9c341e0 Mon Sep 17 00:00:00 2001 From: Michael van Niekerk Date: Fri, 28 Jul 2023 11:37:38 +0200 Subject: [PATCH 2/6] Comments --- examples/rp/Cargo.toml | 1 + examples/rp/src/bin/pio_uart.rs | 345 ++++++++++++++++++++++++-------- 2 files changed, 258 insertions(+), 88 deletions(-) diff --git a/examples/rp/Cargo.toml b/examples/rp/Cargo.toml index c812cb3e..2a018ad0 100644 --- a/examples/rp/Cargo.toml +++ b/examples/rp/Cargo.toml @@ -7,6 +7,7 @@ license = "MIT OR Apache-2.0" [dependencies] embassy-embedded-hal = { version = "0.1.0", path = "../../embassy-embedded-hal", features = ["defmt"] } +embassy-hal-common = { version = "0.1.0", path = "../../embassy-hal-common", features = ["defmt"] } embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] } embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "executor-interrupt", "defmt", "integrated-timers"] } embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["nightly", "unstable-traits", "defmt", "defmt-timestamp-uptime"] } diff --git a/examples/rp/src/bin/pio_uart.rs b/examples/rp/src/bin/pio_uart.rs index 14d05f4d..eeb213e1 100644 --- a/examples/rp/src/bin/pio_uart.rs +++ b/examples/rp/src/bin/pio_uart.rs @@ -1,23 +1,35 @@ -//! This example shows how to use USB (Universal Serial Bus) in the RP2040 chip. +//! This example shows how to use the PIO module in the RP2040 chip to implement a duplex UART. +//! The PIO module is a very powerful peripheral that can be used to implement many different +//! protocols. It is a very flexible state machine that can be programmed to do almost anything. //! -//! This creates a USB serial port that echos. +//! This example opens up a USB device that implements a CDC ACM serial port. It then uses the +//! PIO module to implement a UART that is connected to the USB serial port. This allows you to +//! communicate with a device connected to the RP2040 over USB serial. #![no_std] #![no_main] #![feature(type_alias_impl_trait)] +#![feature(async_fn_in_trait)] -use defmt::{info, panic}; +use defmt::{info, panic, trace}; use embassy_executor::Spawner; -use embassy_futures::join::join; +use embassy_futures::join::{join, join3}; use embassy_rp::bind_interrupts; use embassy_rp::peripherals::{PIO0, USB}; +use embassy_rp::pio::InterruptHandler as PioInterruptHandler; use embassy_rp::usb::{Driver, Instance, InterruptHandler}; -use embassy_usb::class::cdc_acm::{CdcAcmClass, State}; +use embassy_sync::blocking_mutex::raw::ThreadModeRawMutex; +use embassy_sync::channel::Channel; +use embassy_usb::class::cdc_acm::{CdcAcmClass, Receiver, Sender, State}; use embassy_usb::driver::EndpointError; use embassy_usb::{Builder, Config}; -use embassy_rp::pio::{InterruptHandler as PioInterruptHandler}; +use embedded_io::asynch::{Read, Write}; use {defmt_rtt as _, panic_probe as _}; +use crate::uart::PioUart; +use crate::uart_rx::PioUartRx; +use crate::uart_tx::PioUartTx; + bind_interrupts!(struct UsbIrqs { USBCTRL_IRQ => InterruptHandler; }); @@ -69,7 +81,7 @@ async fn main(_spawner: Spawner) { ); // Create classes on the builder. - let mut class = CdcAcmClass::new(&mut builder, &mut state, 64); + let class = CdcAcmClass::new(&mut builder, &mut state, 64); // Build the builder. let mut usb = builder.build(); @@ -77,19 +89,50 @@ async fn main(_spawner: Spawner) { // Run the USB device. let usb_fut = usb.run(); - // Do stuff with the class! - let echo_fut = async { + // PIO UART setup + let uart = PioUart::new(9600, p.PIO0, p.PIN_4, p.PIN_5).await; + let (mut uart_tx, mut uart_rx) = uart.split(); + + // Channels setup + static USB_CHANNEL_TX: Channel = Channel::::new(); + let mut usb_channel_tx_send = USB_CHANNEL_TX.sender(); + let mut usb_channel_tx_recv = USB_CHANNEL_TX.receiver(); + + static UART_CHANNEL_TX: Channel = Channel::::new(); + let mut uart_channel_tx_send = UART_CHANNEL_TX.sender(); + let mut uart_channel_tx_recv = UART_CHANNEL_TX.receiver(); + + let (mut usb_tx, mut usb_rx) = class.split(); + + // Read + write from USB + let usb_future = async { loop { - class.wait_connection().await; + info!("Wait for USB connection"); + usb_rx.wait_connection().await; info!("Connected"); - let _ = echo(&mut class).await; + let _ = join( + usb_read(&mut usb_rx, &mut uart_channel_tx_send), + usb_write(&mut usb_tx, &mut usb_channel_tx_recv), + ) + .await; info!("Disconnected"); } }; + // Read + write from UART + let uart_future = async { + loop { + let _ = join( + uart_read(&mut uart_rx, &mut usb_channel_tx_send), + uart_write(&mut uart_tx, &mut uart_channel_tx_recv), + ) + .await; + } + }; + // Run everything concurrently. // If we had made everything `'static` above instead, we could do this using separate tasks instead. - join(usb_fut, echo_fut).await; + join3(usb_fut, usb_future, uart_future).await; } struct Disconnected {} @@ -103,28 +146,79 @@ impl From for Disconnected { } } -async fn echo<'d, T: Instance + 'd>(class: &mut CdcAcmClass<'d, Driver<'d, T>>) -> Result<(), Disconnected> { +/// Read from the USB and write it to the UART TX send channel +async fn usb_read<'d, T: Instance + 'd>( + usb_rx: &mut Receiver<'d, Driver<'d, T>>, + uart_tx_send: &mut embassy_sync::channel::Sender<'d, ThreadModeRawMutex, u8, 20>, +) -> Result<(), Disconnected> { let mut buf = [0; 64]; loop { - let n = class.read_packet(&mut buf).await?; + let n = usb_rx.read_packet(&mut buf).await?; let data = &buf[..n]; - info!("data: {:x}", data); - class.write_packet(data).await?; + trace!("USB IN: {:x}", data); + for byte in data { + uart_tx_send.send(*byte).await; + } + } +} + +/// Read from the USB TX receive channel and write it to the USB +async fn usb_write<'d, T: Instance + 'd>( + usb_tx: &mut Sender<'d, Driver<'d, T>>, + usb_tx_recv: &mut embassy_sync::channel::Receiver<'d, ThreadModeRawMutex, u8, 20>, +) -> Result<(), Disconnected> { + loop { + let n = usb_tx_recv.recv().await; + let data = [n]; + trace!("USB OUT: {:x}", data); + usb_tx.write_packet(&data).await?; + } +} + +/// Read from the UART and write it to the USB TX send channel +async fn uart_read<'a>( + uart_rx: &mut PioUartRx<'a>, + usb_tx_send: &mut embassy_sync::channel::Sender<'a, ThreadModeRawMutex, u8, 20>, +) -> Result<(), Disconnected> { + let mut buf = [0; 1]; + loop { + let n = uart_rx.read(&mut buf).await.expect("UART read error"); + if n == 0 { + continue; + } + trace!("UART IN: {:x}", buf); + usb_tx_send.send(buf[0]).await; + } +} + +/// Read from the UART TX receive channel and write it to the UART +async fn uart_write<'a>( + uart_tx: &mut PioUartTx<'a>, + uart_rx_recv: &mut embassy_sync::channel::Receiver<'a, ThreadModeRawMutex, u8, 20>, +) -> Result<(), Disconnected> { + loop { + let n = uart_rx_recv.recv().await; + let data = [n]; + trace!("UART OUT: {:x}", data); + let _ = uart_tx.write(&data).await; } } mod uart { - use embassy_rp::peripherals::PIO0; - use embassy_rp::pio::{Common, Pio, PioPin, StateMachine}; - use embassy_rp::Peripheral; + use core::fmt::Debug; + use embassy_rp::peripherals::PIO0; + use embassy_rp::pio::{Pio, PioPin}; + use embassy_rp::Peripheral; + use embedded_io::ErrorKind; + + use crate::uart_rx::PioUartRx; + use crate::uart_tx::PioUartTx; use crate::PioIrqs; pub struct PioUart<'a> { - baud: u64, - pio: Common<'a, PIO0>, - sm0: StateMachine<'a, PIO0, 0>, - sm1: StateMachine<'a, PIO0, 1>, + tx: PioUartTx<'a>, + rx: PioUartRx<'a>, } impl<'a> PioUart<'a> { @@ -135,21 +229,25 @@ mod uart { rx_pin: impl PioPin, ) -> PioUart<'a> { let Pio { - mut common, - mut sm0, - mut sm1, - .. + mut common, sm0, sm1, .. } = Pio::new(pio, PioIrqs); - crate::uart_tx::setup_uart_tx_on_sm0(&mut common, &mut sm0, tx_pin, baud); - crate::uart_rx::setup_uart_rx_on_sm1(&mut common, &mut sm1, rx_pin, baud); + let (tx, origin) = PioUartTx::new(&mut common, sm0, tx_pin, baud, None); + let (rx, _) = PioUartRx::new(&mut common, sm1, rx_pin, baud, Some(origin)); - PioUart { - baud, - pio: common, - sm0, - sm1, - } + PioUart { tx, rx } + } + + pub fn split(self) -> (PioUartTx<'a>, PioUartRx<'a>) { + (self.tx, self.rx) + } + } + #[derive(defmt::Format, Debug)] + pub struct PioUartError {} + + impl embedded_io::Error for PioUartError { + fn kind(&self) -> ErrorKind { + ErrorKind::Other } } } @@ -159,18 +257,27 @@ mod uart_tx { use embassy_rp::peripherals::PIO0; use embassy_rp::pio::{Common, Config, Direction, FifoJoin, PioPin, ShiftDirection, StateMachine}; use embassy_rp::relocate::RelocatedProgram; + use embedded_io::asynch::Write; + use embedded_io::Io; use fixed::traits::ToFixed; use fixed_macro::types::U56F8; - pub fn setup_uart_tx_on_sm0<'a>( - common: &mut Common<'a, PIO0>, - sm_tx: &mut StateMachine<'a, PIO0, 0>, - tx_pin: impl PioPin, - baud: u64, - ) { - let prg = pio_proc::pio_asm!( - r#" - ;.program uart_tx + use crate::uart::PioUartError; + + pub struct PioUartTx<'a> { + sm_tx: StateMachine<'a, PIO0, 0>, + } + + impl<'a> PioUartTx<'a> { + pub fn new( + common: &mut Common<'a, PIO0>, + mut sm_tx: StateMachine<'a, PIO0, 0>, + tx_pin: impl PioPin, + baud: u64, + origin: Option, + ) -> (Self, u8) { + let mut prg = pio_proc::pio_asm!( + r#" .side_set 1 opt ; An 8n1 UART transmit program. @@ -182,23 +289,55 @@ mod uart_tx { out pins, 1 ; Shift 1 bit from OSR to the first OUT pin jmp x-- bitloop [6] ; Each loop iteration is 8 cycles. "# - ); - let tx_pin = common.make_pio_pin(tx_pin); - sm_tx.set_pins(Level::High, &[&tx_pin]); - sm_tx.set_pin_dirs(Direction::Out, &[&tx_pin]); + ); + prg.program.origin = origin; + let tx_pin = common.make_pio_pin(tx_pin); + sm_tx.set_pins(Level::High, &[&tx_pin]); + sm_tx.set_pin_dirs(Direction::Out, &[&tx_pin]); - let relocated = RelocatedProgram::new(&prg.program); - let mut cfg = Config::default(); + let relocated = RelocatedProgram::new(&prg.program); - cfg.use_program(&common.load_program(&relocated), &[&tx_pin]); - cfg.clock_divider = (U56F8!(125_000_000) / (8 * baud)).to_fixed(); - cfg.shift_out.auto_fill = false; - cfg.shift_out.direction = ShiftDirection::Right; - cfg.fifo_join = FifoJoin::TxOnly; - cfg.set_out_pins(&[&tx_pin]); - cfg.set_set_pins(&[&tx_pin]); - sm_tx.set_config(&cfg); - sm_tx.set_enable(true) + let mut cfg = Config::default(); + + cfg.set_out_pins(&[&tx_pin]); + cfg.use_program(&common.load_program(&relocated), &[&tx_pin]); + cfg.shift_out.auto_fill = false; + cfg.shift_out.direction = ShiftDirection::Right; + cfg.fifo_join = FifoJoin::TxOnly; + cfg.clock_divider = (U56F8!(125_000_000) / (8 * baud)).to_fixed(); + sm_tx.set_config(&cfg); + sm_tx.set_enable(true); + + // The 4 state machines of the PIO each have their own program counter that starts taking + // instructions at an offset (origin) of the 32 instruction "space" the PIO device has. + // It is up to the programmer to sort out where to place these instructions. + // From the pio_asm! macro you get a ProgramWithDefines which has a field .program.origin + // which takes an Option. + // + // When you load more than one RelocatedProgram into the PIO, + // you load your first program at origin = 0. + // The RelocatedProgram has .code().count() which returns a usize, + // for which you can then use as your next program's origin. + let offset = relocated.code().count() as u8 + origin.unwrap_or_default(); + (Self { sm_tx }, offset) + } + + pub async fn write_u8(&mut self, data: u8) { + self.sm_tx.tx().wait_push(data as u32).await; + } + } + + impl Io for PioUartTx<'_> { + type Error = PioUartError; + } + + impl Write for PioUartTx<'_> { + async fn write(&mut self, buf: &[u8]) -> Result { + for byte in buf { + self.write_u8(*byte).await; + } + Ok(buf.len()) + } } } @@ -207,19 +346,27 @@ mod uart_rx { use embassy_rp::peripherals::PIO0; use embassy_rp::pio::{Common, Config, Direction, FifoJoin, PioPin, ShiftDirection, StateMachine}; use embassy_rp::relocate::RelocatedProgram; + use embedded_io::asynch::Read; + use embedded_io::Io; use fixed::traits::ToFixed; use fixed_macro::types::U56F8; - pub fn setup_uart_rx_on_sm1<'a>( - common: &mut Common<'a, PIO0>, - sm_rx: &mut StateMachine<'a, PIO0, 1>, - rx_pin: impl PioPin, - baud: u64, - ) { - let prg = pio_proc::pio_asm!( - r#" - ;.program uart_rx + use crate::uart::PioUartError; + pub struct PioUartRx<'a> { + sm_rx: StateMachine<'a, PIO0, 1>, + } + + impl<'a> PioUartRx<'a> { + pub fn new( + common: &mut Common<'a, PIO0>, + mut sm_rx: StateMachine<'a, PIO0, 1>, + rx_pin: impl PioPin, + baud: u64, + origin: Option, + ) -> (Self, u8) { + let mut prg = pio_proc::pio_asm!( + r#" ; Slightly more fleshed-out 8n1 UART receiver which handles framing errors and ; break conditions more gracefully. ; IN pin 0 and JMP pin are both mapped to the GPIO used as UART RX. @@ -227,36 +374,58 @@ mod uart_rx { start: wait 0 pin 0 ; Stall until start bit is asserted set x, 7 [10] ; Preload bit counter, then delay until halfway through - bitloop: ; the first data bit (12 cycles incl wait, set). + rx_bitloop: ; the first data bit (12 cycles incl wait, set). in pins, 1 ; Shift data bit into ISR - jmp x-- bitloop [6] ; Loop 8 times, each loop iteration is 8 cycles - jmp pin good_stop ; Check stop bit (should be high) + jmp x-- rx_bitloop [6] ; Loop 8 times, each loop iteration is 8 cycles + jmp pin good_rx_stop ; Check stop bit (should be high) irq 4 rel ; Either a framing error or a break. Set a sticky flag, wait 1 pin 0 ; and wait for line to return to idle state. jmp start ; Don't push data if we didn't see good framing. - good_stop: ; No delay before returning to start; a little slack is + good_rx_stop: ; No delay before returning to start; a little slack is push ; important in case the TX clock is slightly too fast. "# - ); + ); + prg.program.origin = origin; + let relocated = RelocatedProgram::new(&prg.program); + let mut cfg = Config::default(); + cfg.use_program(&common.load_program(&relocated), &[]); - let rx_pin = common.make_pio_pin(rx_pin); - sm_rx.set_pins(Level::High, &[&rx_pin]); - sm_rx.set_pin_dirs(Direction::In, &[&rx_pin]); + let rx_pin = common.make_pio_pin(rx_pin); + sm_rx.set_pins(Level::High, &[&rx_pin]); + cfg.set_in_pins(&[&rx_pin]); + cfg.set_jmp_pin(&rx_pin); + sm_rx.set_pin_dirs(Direction::In, &[&rx_pin]); - let relocated = RelocatedProgram::new(&prg.program); - let mut cfg = Config::default(); + cfg.clock_divider = (U56F8!(125_000_000) / (8 * baud)).to_fixed(); + cfg.shift_out.auto_fill = false; + cfg.shift_out.direction = ShiftDirection::Right; + cfg.fifo_join = FifoJoin::RxOnly; + sm_rx.set_config(&cfg); + sm_rx.set_enable(true); - cfg.use_program(&common.load_program(&relocated), &[&rx_pin]); - cfg.clock_divider = (U56F8!(125_000_000) / (8 * baud)).to_fixed(); - cfg.shift_out.auto_fill = false; - cfg.shift_out.direction = ShiftDirection::Right; - cfg.fifo_join = FifoJoin::RxOnly; - cfg.set_in_pins(&[&rx_pin]); - cfg.set_jmp_pin(&rx_pin); - // cfg.set_set_pins(&[&rx_pin]); - sm_rx.set_config(&cfg); - sm_rx.set_enable(true) + let offset = relocated.code().count() as u8 + origin.unwrap_or_default(); + (Self { sm_rx }, offset) + } + + pub async fn read_u8(&mut self) -> u8 { + self.sm_rx.rx().wait_pull().await as u8 + } + } + + impl Io for PioUartRx<'_> { + type Error = PioUartError; + } + + impl Read for PioUartRx<'_> { + async fn read(&mut self, buf: &mut [u8]) -> Result { + let mut i = 0; + while i < buf.len() { + buf[i] = self.read_u8().await; + i += 1; + } + Ok(i) + } } } From 0f1ff77fcc3c085f9969bac4963d784c022e6044 Mon Sep 17 00:00:00 2001 From: Michael van Niekerk Date: Fri, 28 Jul 2023 11:38:08 +0200 Subject: [PATCH 3/6] Comments --- examples/rp/.idea/.gitignore | 8 -------- examples/rp/.idea/modules.xml | 8 -------- examples/rp/.idea/rp.iml | 12 ------------ examples/rp/.idea/vcs.xml | 6 ------ 4 files changed, 34 deletions(-) delete mode 100644 examples/rp/.idea/.gitignore delete mode 100644 examples/rp/.idea/modules.xml delete mode 100644 examples/rp/.idea/rp.iml delete mode 100644 examples/rp/.idea/vcs.xml diff --git a/examples/rp/.idea/.gitignore b/examples/rp/.idea/.gitignore deleted file mode 100644 index 13566b81..00000000 --- a/examples/rp/.idea/.gitignore +++ /dev/null @@ -1,8 +0,0 @@ -# Default ignored files -/shelf/ -/workspace.xml -# Editor-based HTTP Client requests -/httpRequests/ -# Datasource local storage ignored files -/dataSources/ -/dataSources.local.xml diff --git a/examples/rp/.idea/modules.xml b/examples/rp/.idea/modules.xml deleted file mode 100644 index 06ff4b23..00000000 --- a/examples/rp/.idea/modules.xml +++ /dev/null @@ -1,8 +0,0 @@ - - - - - - - - \ No newline at end of file diff --git a/examples/rp/.idea/rp.iml b/examples/rp/.idea/rp.iml deleted file mode 100644 index 9b4cf845..00000000 --- a/examples/rp/.idea/rp.iml +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - - - - \ No newline at end of file diff --git a/examples/rp/.idea/vcs.xml b/examples/rp/.idea/vcs.xml deleted file mode 100644 index b2bdec2d..00000000 --- a/examples/rp/.idea/vcs.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - \ No newline at end of file From 91338adc159dd026ba56dcb4e991ed9f60053bb0 Mon Sep 17 00:00:00 2001 From: Michael van Niekerk Date: Fri, 28 Jul 2023 11:56:59 +0200 Subject: [PATCH 4/6] Don't include embedded-hal-common --- examples/rp/Cargo.toml | 1 - 1 file changed, 1 deletion(-) diff --git a/examples/rp/Cargo.toml b/examples/rp/Cargo.toml index 2a018ad0..c812cb3e 100644 --- a/examples/rp/Cargo.toml +++ b/examples/rp/Cargo.toml @@ -7,7 +7,6 @@ license = "MIT OR Apache-2.0" [dependencies] embassy-embedded-hal = { version = "0.1.0", path = "../../embassy-embedded-hal", features = ["defmt"] } -embassy-hal-common = { version = "0.1.0", path = "../../embassy-hal-common", features = ["defmt"] } embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] } embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "executor-interrupt", "defmt", "integrated-timers"] } embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["nightly", "unstable-traits", "defmt", "defmt-timestamp-uptime"] } From 146c744223056561c6be61dda791993d939d0ae0 Mon Sep 17 00:00:00 2001 From: Michael van Niekerk Date: Fri, 28 Jul 2023 12:56:31 +0200 Subject: [PATCH 5/6] Fixes as per PR --- examples/rp/src/bin/pio_uart.rs | 114 ++++++++++++++------------------ 1 file changed, 48 insertions(+), 66 deletions(-) diff --git a/examples/rp/src/bin/pio_uart.rs b/examples/rp/src/bin/pio_uart.rs index eeb213e1..c978f8f0 100644 --- a/examples/rp/src/bin/pio_uart.rs +++ b/examples/rp/src/bin/pio_uart.rs @@ -19,7 +19,7 @@ use embassy_rp::peripherals::{PIO0, USB}; use embassy_rp::pio::InterruptHandler as PioInterruptHandler; use embassy_rp::usb::{Driver, Instance, InterruptHandler}; use embassy_sync::blocking_mutex::raw::ThreadModeRawMutex; -use embassy_sync::channel::Channel; +use embassy_sync::pipe::Pipe; use embassy_usb::class::cdc_acm::{CdcAcmClass, Receiver, Sender, State}; use embassy_usb::driver::EndpointError; use embassy_usb::{Builder, Config}; @@ -30,11 +30,8 @@ use crate::uart::PioUart; use crate::uart_rx::PioUartRx; use crate::uart_tx::PioUartTx; -bind_interrupts!(struct UsbIrqs { +bind_interrupts!(struct Irqs { USBCTRL_IRQ => InterruptHandler; -}); - -bind_interrupts!(struct PioIrqs { PIO0_IRQ_0 => PioInterruptHandler; }); @@ -45,7 +42,7 @@ async fn main(_spawner: Spawner) { let p = embassy_rp::init(Default::default()); // Create the driver, from the HAL. - let driver = Driver::new(p.USB, UsbIrqs); + let driver = Driver::new(p.USB, Irqs); // Create embassy-usb Config let mut config = Config::new(0xc0de, 0xcafe); @@ -90,17 +87,17 @@ async fn main(_spawner: Spawner) { let usb_fut = usb.run(); // PIO UART setup - let uart = PioUart::new(9600, p.PIO0, p.PIN_4, p.PIN_5).await; + let uart = PioUart::new(9600, p.PIO0, p.PIN_4, p.PIN_5); let (mut uart_tx, mut uart_rx) = uart.split(); - // Channels setup - static USB_CHANNEL_TX: Channel = Channel::::new(); - let mut usb_channel_tx_send = USB_CHANNEL_TX.sender(); - let mut usb_channel_tx_recv = USB_CHANNEL_TX.receiver(); + // Pipe setup + static USB_PIPE: Pipe = Pipe::new(); + let mut usb_pipe_writer = USB_PIPE.writer(); + let mut usb_pipe_reader = USB_PIPE.reader(); - static UART_CHANNEL_TX: Channel = Channel::::new(); - let mut uart_channel_tx_send = UART_CHANNEL_TX.sender(); - let mut uart_channel_tx_recv = UART_CHANNEL_TX.receiver(); + static UART_PIPE: Pipe = Pipe::new(); + let mut uart_pipe_writer = UART_PIPE.writer(); + let mut uart_pipe_reader = UART_PIPE.reader(); let (mut usb_tx, mut usb_rx) = class.split(); @@ -111,8 +108,8 @@ async fn main(_spawner: Spawner) { usb_rx.wait_connection().await; info!("Connected"); let _ = join( - usb_read(&mut usb_rx, &mut uart_channel_tx_send), - usb_write(&mut usb_tx, &mut usb_channel_tx_recv), + usb_read(&mut usb_rx, &mut uart_pipe_writer), + usb_write(&mut usb_tx, &mut usb_pipe_reader), ) .await; info!("Disconnected"); @@ -120,15 +117,10 @@ async fn main(_spawner: Spawner) { }; // Read + write from UART - let uart_future = async { - loop { - let _ = join( - uart_read(&mut uart_rx, &mut usb_channel_tx_send), - uart_write(&mut uart_tx, &mut uart_channel_tx_recv), - ) - .await; - } - }; + let uart_future = join( + uart_read(&mut uart_rx, &mut usb_pipe_writer), + uart_write(&mut uart_tx, &mut uart_pipe_reader), + ); // Run everything concurrently. // If we had made everything `'static` above instead, we could do this using separate tasks instead. @@ -146,75 +138,73 @@ impl From for Disconnected { } } -/// Read from the USB and write it to the UART TX send channel +/// Read from the USB and write it to the UART TX pipe async fn usb_read<'d, T: Instance + 'd>( usb_rx: &mut Receiver<'d, Driver<'d, T>>, - uart_tx_send: &mut embassy_sync::channel::Sender<'d, ThreadModeRawMutex, u8, 20>, + uart_pipe_writer: &mut embassy_sync::pipe::Writer<'static, ThreadModeRawMutex, 20>, ) -> Result<(), Disconnected> { let mut buf = [0; 64]; loop { let n = usb_rx.read_packet(&mut buf).await?; let data = &buf[..n]; trace!("USB IN: {:x}", data); - for byte in data { - uart_tx_send.send(*byte).await; - } + uart_pipe_writer.write(data).await; } } -/// Read from the USB TX receive channel and write it to the USB +/// Read from the USB TX pipe and write it to the USB async fn usb_write<'d, T: Instance + 'd>( usb_tx: &mut Sender<'d, Driver<'d, T>>, - usb_tx_recv: &mut embassy_sync::channel::Receiver<'d, ThreadModeRawMutex, u8, 20>, + usb_pipe_reader: &mut embassy_sync::pipe::Reader<'d, ThreadModeRawMutex, 20>, ) -> Result<(), Disconnected> { + let mut buf = [0; 64]; loop { - let n = usb_tx_recv.recv().await; - let data = [n]; + let n = usb_pipe_reader.read(&mut buf).await; + let data = &buf[..n]; trace!("USB OUT: {:x}", data); usb_tx.write_packet(&data).await?; } } -/// Read from the UART and write it to the USB TX send channel +/// Read from the UART and write it to the USB TX pipe async fn uart_read<'a>( uart_rx: &mut PioUartRx<'a>, - usb_tx_send: &mut embassy_sync::channel::Sender<'a, ThreadModeRawMutex, u8, 20>, -) -> Result<(), Disconnected> { - let mut buf = [0; 1]; + usb_pipe_writer: &mut embassy_sync::pipe::Writer<'static, ThreadModeRawMutex, 20>, +) -> ! { + let mut buf = [0; 64]; loop { let n = uart_rx.read(&mut buf).await.expect("UART read error"); if n == 0 { continue; } + let data = &buf[..n]; trace!("UART IN: {:x}", buf); - usb_tx_send.send(buf[0]).await; + usb_pipe_writer.write(data).await; } } -/// Read from the UART TX receive channel and write it to the UART +/// Read from the UART TX pipe and write it to the UART async fn uart_write<'a>( uart_tx: &mut PioUartTx<'a>, - uart_rx_recv: &mut embassy_sync::channel::Receiver<'a, ThreadModeRawMutex, u8, 20>, -) -> Result<(), Disconnected> { + uart_pipe_reader: &mut embassy_sync::pipe::Reader<'a, ThreadModeRawMutex, 20>, +) -> ! { + let mut buf = [0; 64]; loop { - let n = uart_rx_recv.recv().await; - let data = [n]; + let n = uart_pipe_reader.read(&mut buf).await; + let data = &buf[..n]; trace!("UART OUT: {:x}", data); let _ = uart_tx.write(&data).await; } } mod uart { - use core::fmt::Debug; - use embassy_rp::peripherals::PIO0; use embassy_rp::pio::{Pio, PioPin}; use embassy_rp::Peripheral; - use embedded_io::ErrorKind; use crate::uart_rx::PioUartRx; use crate::uart_tx::PioUartTx; - use crate::PioIrqs; + use crate::Irqs; pub struct PioUart<'a> { tx: PioUartTx<'a>, @@ -222,7 +212,7 @@ mod uart { } impl<'a> PioUart<'a> { - pub async fn new( + pub fn new( baud: u64, pio: impl Peripheral

+ 'a, tx_pin: impl PioPin, @@ -230,7 +220,7 @@ mod uart { ) -> PioUart<'a> { let Pio { mut common, sm0, sm1, .. - } = Pio::new(pio, PioIrqs); + } = Pio::new(pio, Irqs); let (tx, origin) = PioUartTx::new(&mut common, sm0, tx_pin, baud, None); let (rx, _) = PioUartRx::new(&mut common, sm1, rx_pin, baud, Some(origin)); @@ -242,17 +232,11 @@ mod uart { (self.tx, self.rx) } } - #[derive(defmt::Format, Debug)] - pub struct PioUartError {} - - impl embedded_io::Error for PioUartError { - fn kind(&self) -> ErrorKind { - ErrorKind::Other - } - } } mod uart_tx { + use core::convert::Infallible; + use embassy_rp::gpio::Level; use embassy_rp::peripherals::PIO0; use embassy_rp::pio::{Common, Config, Direction, FifoJoin, PioPin, ShiftDirection, StateMachine}; @@ -262,8 +246,6 @@ mod uart_tx { use fixed::traits::ToFixed; use fixed_macro::types::U56F8; - use crate::uart::PioUartError; - pub struct PioUartTx<'a> { sm_tx: StateMachine<'a, PIO0, 0>, } @@ -328,11 +310,11 @@ mod uart_tx { } impl Io for PioUartTx<'_> { - type Error = PioUartError; + type Error = Infallible; } impl Write for PioUartTx<'_> { - async fn write(&mut self, buf: &[u8]) -> Result { + async fn write(&mut self, buf: &[u8]) -> Result { for byte in buf { self.write_u8(*byte).await; } @@ -342,6 +324,8 @@ mod uart_tx { } mod uart_rx { + use core::convert::Infallible; + use embassy_rp::gpio::Level; use embassy_rp::peripherals::PIO0; use embassy_rp::pio::{Common, Config, Direction, FifoJoin, PioPin, ShiftDirection, StateMachine}; @@ -351,8 +335,6 @@ mod uart_rx { use fixed::traits::ToFixed; use fixed_macro::types::U56F8; - use crate::uart::PioUartError; - pub struct PioUartRx<'a> { sm_rx: StateMachine<'a, PIO0, 1>, } @@ -415,11 +397,11 @@ mod uart_rx { } impl Io for PioUartRx<'_> { - type Error = PioUartError; + type Error = Infallible; } impl Read for PioUartRx<'_> { - async fn read(&mut self, buf: &mut [u8]) -> Result { + async fn read(&mut self, buf: &mut [u8]) -> Result { let mut i = 0; while i < buf.len() { buf[i] = self.read_u8().await; From d5f9d17b7c12c73cf16aa7414ce819bbd06efc2e Mon Sep 17 00:00:00 2001 From: Dario Nieuwenhuis Date: Fri, 28 Jul 2023 13:38:26 +0200 Subject: [PATCH 6/6] Make pipes local vars. --- examples/rp/src/bin/pio_uart.rs | 30 +++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/examples/rp/src/bin/pio_uart.rs b/examples/rp/src/bin/pio_uart.rs index c978f8f0..ca1c7f39 100644 --- a/examples/rp/src/bin/pio_uart.rs +++ b/examples/rp/src/bin/pio_uart.rs @@ -18,7 +18,7 @@ use embassy_rp::bind_interrupts; use embassy_rp::peripherals::{PIO0, USB}; use embassy_rp::pio::InterruptHandler as PioInterruptHandler; use embassy_rp::usb::{Driver, Instance, InterruptHandler}; -use embassy_sync::blocking_mutex::raw::ThreadModeRawMutex; +use embassy_sync::blocking_mutex::raw::NoopRawMutex; use embassy_sync::pipe::Pipe; use embassy_usb::class::cdc_acm::{CdcAcmClass, Receiver, Sender, State}; use embassy_usb::driver::EndpointError; @@ -91,13 +91,13 @@ async fn main(_spawner: Spawner) { let (mut uart_tx, mut uart_rx) = uart.split(); // Pipe setup - static USB_PIPE: Pipe = Pipe::new(); - let mut usb_pipe_writer = USB_PIPE.writer(); - let mut usb_pipe_reader = USB_PIPE.reader(); + let usb_pipe: Pipe = Pipe::new(); + let mut usb_pipe_writer = usb_pipe.writer(); + let mut usb_pipe_reader = usb_pipe.reader(); - static UART_PIPE: Pipe = Pipe::new(); - let mut uart_pipe_writer = UART_PIPE.writer(); - let mut uart_pipe_reader = UART_PIPE.reader(); + let uart_pipe: Pipe = Pipe::new(); + let mut uart_pipe_writer = uart_pipe.writer(); + let mut uart_pipe_reader = uart_pipe.reader(); let (mut usb_tx, mut usb_rx) = class.split(); @@ -141,7 +141,7 @@ impl From for Disconnected { /// Read from the USB and write it to the UART TX pipe async fn usb_read<'d, T: Instance + 'd>( usb_rx: &mut Receiver<'d, Driver<'d, T>>, - uart_pipe_writer: &mut embassy_sync::pipe::Writer<'static, ThreadModeRawMutex, 20>, + uart_pipe_writer: &mut embassy_sync::pipe::Writer<'_, NoopRawMutex, 20>, ) -> Result<(), Disconnected> { let mut buf = [0; 64]; loop { @@ -155,7 +155,7 @@ async fn usb_read<'d, T: Instance + 'd>( /// Read from the USB TX pipe and write it to the USB async fn usb_write<'d, T: Instance + 'd>( usb_tx: &mut Sender<'d, Driver<'d, T>>, - usb_pipe_reader: &mut embassy_sync::pipe::Reader<'d, ThreadModeRawMutex, 20>, + usb_pipe_reader: &mut embassy_sync::pipe::Reader<'_, NoopRawMutex, 20>, ) -> Result<(), Disconnected> { let mut buf = [0; 64]; loop { @@ -167,9 +167,9 @@ async fn usb_write<'d, T: Instance + 'd>( } /// Read from the UART and write it to the USB TX pipe -async fn uart_read<'a>( - uart_rx: &mut PioUartRx<'a>, - usb_pipe_writer: &mut embassy_sync::pipe::Writer<'static, ThreadModeRawMutex, 20>, +async fn uart_read( + uart_rx: &mut PioUartRx<'_>, + usb_pipe_writer: &mut embassy_sync::pipe::Writer<'_, NoopRawMutex, 20>, ) -> ! { let mut buf = [0; 64]; loop { @@ -184,9 +184,9 @@ async fn uart_read<'a>( } /// Read from the UART TX pipe and write it to the UART -async fn uart_write<'a>( - uart_tx: &mut PioUartTx<'a>, - uart_pipe_reader: &mut embassy_sync::pipe::Reader<'a, ThreadModeRawMutex, 20>, +async fn uart_write( + uart_tx: &mut PioUartTx<'_>, + uart_pipe_reader: &mut embassy_sync::pipe::Reader<'_, NoopRawMutex, 20>, ) -> ! { let mut buf = [0; 64]; loop {