From 87795cbca84a67ce9c5bdb5c3043b41251d75bbc Mon Sep 17 00:00:00 2001 From: Fabian Kunze Date: Sun, 7 May 2023 01:00:13 +0200 Subject: [PATCH 1/6] added example multi priority executors rp2040 --- embassy-rp/Cargo.toml | 2 +- embassy-rp/src/interrupt.rs | 6 ++ examples/rp/Cargo.toml | 2 +- examples/rp/src/bin/multiprio.rs | 152 +++++++++++++++++++++++++++++++ 4 files changed, 160 insertions(+), 2 deletions(-) create mode 100644 examples/rp/src/bin/multiprio.rs diff --git a/embassy-rp/Cargo.toml b/embassy-rp/Cargo.toml index 59d0bf338..ea8f54f36 100644 --- a/embassy-rp/Cargo.toml +++ b/embassy-rp/Cargo.toml @@ -61,7 +61,7 @@ embedded-storage = { version = "0.3" } rand_core = "0.6.4" fixed = "1.23.1" -rp-pac = { version = "2", features = ["rt"] } +rp-pac = { version = "2", features = ["rt"], path = "../../rp-pac" } embedded-hal-02 = { package = "embedded-hal", version = "0.2.6", features = ["unproven"] } embedded-hal-1 = { package = "embedded-hal", version = "=1.0.0-alpha.10", optional = true} diff --git a/embassy-rp/src/interrupt.rs b/embassy-rp/src/interrupt.rs index f21a5433b..989f5dc2d 100644 --- a/embassy-rp/src/interrupt.rs +++ b/embassy-rp/src/interrupt.rs @@ -34,3 +34,9 @@ declare!(ADC_IRQ_FIFO); declare!(I2C0_IRQ); declare!(I2C1_IRQ); declare!(RTC_IRQ); +declare!(SWI_IRQ_0); +declare!(SWI_IRQ_1); +declare!(SWI_IRQ_2); +declare!(SWI_IRQ_3); +declare!(SWI_IRQ_4); +declare!(SWI_IRQ_5); diff --git a/examples/rp/Cargo.toml b/examples/rp/Cargo.toml index 57f6f5c67..3f74129a4 100644 --- a/examples/rp/Cargo.toml +++ b/examples/rp/Cargo.toml @@ -8,7 +8,7 @@ license = "MIT OR Apache-2.0" [dependencies] embassy-embedded-hal = { version = "0.1.0", path = "../../embassy-embedded-hal", features = ["defmt"] } embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] } -embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["arch-cortex-m", "executor-thread", "defmt", "integrated-timers"] } +embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["arch-cortex-m", "executor-thread", "executor-interrupt", "defmt", "integrated-timers"] } embassy-time = { version = "0.1.0", path = "../../embassy-time", features = ["nightly", "unstable-traits", "defmt", "defmt-timestamp-uptime"] } embassy-rp = { version = "0.1.0", path = "../../embassy-rp", features = ["defmt", "unstable-traits", "nightly", "unstable-pac", "time-driver", "critical-section-impl"] } embassy-usb = { version = "0.1.0", path = "../../embassy-usb", features = ["defmt"] } diff --git a/examples/rp/src/bin/multiprio.rs b/examples/rp/src/bin/multiprio.rs new file mode 100644 index 000000000..2f79ba49e --- /dev/null +++ b/examples/rp/src/bin/multiprio.rs @@ -0,0 +1,152 @@ +//! This example showcases how to create multiple Executor instances to run tasks at +//! different priority levels. +//! +//! Low priority executor runs in thread mode (not interrupt), and uses `sev` for signaling +//! there's work in the queue, and `wfe` for waiting for work. +//! +//! Medium and high priority executors run in two interrupts with different priorities. +//! Signaling work is done by pending the interrupt. No "waiting" needs to be done explicitly, since +//! when there's work the interrupt will trigger and run the executor. +//! +//! Sample output below. Note that high priority ticks can interrupt everything else, and +//! medium priority computations can interrupt low priority computations, making them to appear +//! to take significantly longer time. +//! +//! ```not_rust +//! [med] Starting long computation +//! [med] done in 992 ms +//! [high] tick! +//! [low] Starting long computation +//! [med] Starting long computation +//! [high] tick! +//! [high] tick! +//! [med] done in 993 ms +//! [med] Starting long computation +//! [high] tick! +//! [high] tick! +//! [med] done in 993 ms +//! [low] done in 3972 ms +//! [med] Starting long computation +//! [high] tick! +//! [high] tick! +//! [med] done in 993 ms +//! ``` +//! +//! For comparison, try changing the code so all 3 tasks get spawned on the low priority executor. +//! You will get an output like the following. Note that no computation is ever interrupted. +//! +//! ```not_rust +//! [high] tick! +//! [med] Starting long computation +//! [med] done in 496 ms +//! [low] Starting long computation +//! [low] done in 992 ms +//! [med] Starting long computation +//! [med] done in 496 ms +//! [high] tick! +//! [low] Starting long computation +//! [low] done in 992 ms +//! [high] tick! +//! [med] Starting long computation +//! [med] done in 496 ms +//! [high] tick! +//! ``` +//! + +#![no_std] +#![no_main] +#![feature(type_alias_impl_trait)] + +use core::mem; + +use cortex_m::peripheral::NVIC; +use cortex_m_rt::entry; +use defmt::{info, unwrap}; +use embassy_rp::executor::{Executor, InterruptExecutor}; +use embassy_rp::interrupt; +use embassy_rp::pac::Interrupt; +use embassy_time::{Duration, Instant, Timer, TICK_HZ}; +use static_cell::StaticCell; +use {defmt_rtt as _, panic_probe as _}; + +#[embassy_executor::task] +async fn run_high() { + loop { + info!(" [high] tick!"); + Timer::after(Duration::from_ticks(673740)).await; + } +} + +#[embassy_executor::task] +async fn run_med() { + loop { + let start = Instant::now(); + info!(" [med] Starting long computation"); + + // Spin-wait to simulate a long CPU computation + cortex_m::asm::delay(125_000_000); // ~1 second + + let end = Instant::now(); + let ms = end.duration_since(start).as_ticks() * 1000 / TICK_HZ; + info!(" [med] done in {} ms", ms); + + Timer::after(Duration::from_ticks(53421)).await; + } +} + +#[embassy_executor::task] +async fn run_low() { + loop { + let start = Instant::now(); + info!("[low] Starting long computation"); + + // Spin-wait to simulate a long CPU computation + cortex_m::asm::delay(250_000_000); // ~2 seconds + + let end = Instant::now(); + let ms = end.duration_since(start).as_ticks() * 1000 / TICK_HZ; + info!("[low] done in {} ms", ms); + + Timer::after(Duration::from_ticks(82983)).await; + } +} + +static EXECUTOR_HIGH: InterruptExecutor = InterruptExecutor::new(); +static EXECUTOR_MED: InterruptExecutor = InterruptExecutor::new(); +static EXECUTOR_LOW: StaticCell = StaticCell::new(); + +#[interrupt] +unsafe fn SWI_IRQ_1() { + EXECUTOR_HIGH.on_interrupt() +} + +#[interrupt] +unsafe fn SWI_IRQ_0() { + EXECUTOR_MED.on_interrupt() +} + +#[entry] +fn main() -> ! { + info!("Hello World!"); + + let _p = embassy_rp::init(Default::default()); + let mut nvic: NVIC = unsafe { mem::transmute(()) }; + + // High-priority executor: SWI_IRQ_1, priority level 2 + unsafe { nvic.set_priority(Interrupt::SWI_IRQ_1, 2 << 6) }; + info!("bla: {}", NVIC::get_priority(Interrupt::SWI_IRQ_1)); + let spawner = EXECUTOR_HIGH.start(Interrupt::SWI_IRQ_1); + unwrap!(spawner.spawn(run_high())); + + // Medium-priority executor: SWI_IRQ_0, priority level 3 + unsafe { nvic.set_priority(Interrupt::SWI_IRQ_0, 3 << 6) }; + info!("bla: {}", NVIC::get_priority(Interrupt::SWI_IRQ_0)); + let spawner = EXECUTOR_MED.start(Interrupt::SWI_IRQ_0); + unwrap!(spawner.spawn(run_med())); + + // Low priority executor: runs in thread mode, using WFE/SEV + let executor = EXECUTOR_LOW.init(Executor::new()); + executor.run(|spawner| { + unwrap!(spawner.spawn(run_low())); + }); +} From fb2d5b484aa9533f29528d0789fac559d48859ad Mon Sep 17 00:00:00 2001 From: Fabian Kunze Date: Sun, 7 May 2023 01:18:19 +0200 Subject: [PATCH 2/6] changed relative cargo.toml dependency to github revision --- embassy-rp/Cargo.toml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/embassy-rp/Cargo.toml b/embassy-rp/Cargo.toml index ea8f54f36..2748c0591 100644 --- a/embassy-rp/Cargo.toml +++ b/embassy-rp/Cargo.toml @@ -61,7 +61,7 @@ embedded-storage = { version = "0.3" } rand_core = "0.6.4" fixed = "1.23.1" -rp-pac = { version = "2", features = ["rt"], path = "../../rp-pac" } +rp-pac = { features = ["rt"], git = "https://github.com/fakusb/rp-pac.git", rev = "b1e0a150f37efb69644f5474d879e9180eeb167b" } embedded-hal-02 = { package = "embedded-hal", version = "0.2.6", features = ["unproven"] } embedded-hal-1 = { package = "embedded-hal", version = "=1.0.0-alpha.10", optional = true} From 2910b09cba432d79befa42a7f994c60dfe832d40 Mon Sep 17 00:00:00 2001 From: Fabian Kunze Date: Mon, 8 May 2023 17:53:39 +0200 Subject: [PATCH 3/6] bumped rp-pac version --- embassy-rp/Cargo.toml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/embassy-rp/Cargo.toml b/embassy-rp/Cargo.toml index 2748c0591..b2b7fb083 100644 --- a/embassy-rp/Cargo.toml +++ b/embassy-rp/Cargo.toml @@ -61,7 +61,7 @@ embedded-storage = { version = "0.3" } rand_core = "0.6.4" fixed = "1.23.1" -rp-pac = { features = ["rt"], git = "https://github.com/fakusb/rp-pac.git", rev = "b1e0a150f37efb69644f5474d879e9180eeb167b" } +rp-pac = { version = "3", features = ["rt"] } embedded-hal-02 = { package = "embedded-hal", version = "0.2.6", features = ["unproven"] } embedded-hal-1 = { package = "embedded-hal", version = "=1.0.0-alpha.10", optional = true} From 0584312ef0324d2ac67dbb9517176fabf628eec9 Mon Sep 17 00:00:00 2001 From: Dirk Stolle Date: Mon, 8 May 2023 23:25:01 +0200 Subject: [PATCH 4/6] Fix some typos --- docs/modules/ROOT/pages/getting_started.adoc | 2 +- embassy-hal-common/src/atomic_ring_buffer.rs | 4 ++-- embassy-nrf/src/nvmc.rs | 2 +- embassy-nrf/src/twim.rs | 2 +- embassy-nrf/src/twis.rs | 14 +++++++------- embassy-rp/src/flash.rs | 2 +- embassy-rp/src/i2c.rs | 2 +- embassy-rp/src/uart/buffered.rs | 2 +- embassy-rp/src/uart/mod.rs | 4 ++-- embassy-stm32/src/time_driver.rs | 2 +- embassy-stm32/src/usart/mod.rs | 6 +++--- embassy-usb-driver/src/lib.rs | 2 +- embassy-usb/src/class/cdc_ncm/mod.rs | 4 ++-- embassy-usb/src/class/hid.rs | 2 +- embassy-usb/src/msos.rs | 2 +- examples/nrf52840/src/bin/pubsub.rs | 4 ++-- examples/nrf52840/src/bin/usb_serial.rs | 2 +- examples/nrf52840/src/bin/usb_serial_multitask.rs | 2 +- examples/nrf52840/src/bin/usb_serial_winusb.rs | 2 +- examples/rp/src/bin/usb_serial.rs | 2 +- .../stm32f0/src/bin/button_controlled_blink.rs | 4 ++-- examples/stm32f4/src/bin/usb_serial.rs | 2 +- examples/stm32f7/src/bin/usb_serial.rs | 2 +- examples/stm32h5/src/bin/usb_serial.rs | 2 +- examples/stm32h7/src/bin/usb_serial.rs | 2 +- examples/stm32l4/src/bin/usb_serial.rs | 2 +- examples/stm32u5/src/bin/usb_serial.rs | 2 +- examples/stm32wl/src/bin/uart_async.rs | 2 +- 28 files changed, 41 insertions(+), 41 deletions(-) diff --git a/docs/modules/ROOT/pages/getting_started.adoc b/docs/modules/ROOT/pages/getting_started.adoc index 9015d7845..881e449b6 100644 --- a/docs/modules/ROOT/pages/getting_started.adoc +++ b/docs/modules/ROOT/pages/getting_started.adoc @@ -49,7 +49,7 @@ cd examples/nrf52840 cargo run --bin blinky --release ---- -== Whats next? +== What's next? Congratulations, you have your first Embassy application running! Here are some alternatives on where to go from here: diff --git a/embassy-hal-common/src/atomic_ring_buffer.rs b/embassy-hal-common/src/atomic_ring_buffer.rs index afd3ce1de..0eb39cb33 100644 --- a/embassy-hal-common/src/atomic_ring_buffer.rs +++ b/embassy-hal-common/src/atomic_ring_buffer.rs @@ -133,7 +133,7 @@ impl<'a> Writer<'a> { /// Push one data byte. /// - /// Returns true if pushed succesfully. + /// Returns true if pushed successfully. pub fn push_one(&mut self, val: u8) -> bool { let n = self.push(|f| match f { [] => 0, @@ -265,7 +265,7 @@ impl<'a> Reader<'a> { /// Pop one data byte. /// - /// Returns true if popped succesfully. + /// Returns true if popped successfully. pub fn pop_one(&mut self) -> Option { let mut res = None; self.pop(|f| match f { diff --git a/embassy-nrf/src/nvmc.rs b/embassy-nrf/src/nvmc.rs index 6f48853d5..91a5a272f 100644 --- a/embassy-nrf/src/nvmc.rs +++ b/embassy-nrf/src/nvmc.rs @@ -24,7 +24,7 @@ pub const FLASH_SIZE: usize = crate::chip::FLASH_SIZE; #[derive(Debug, Copy, Clone, PartialEq, Eq)] #[cfg_attr(feature = "defmt", derive(defmt::Format))] pub enum Error { - /// Opration using a location not in flash. + /// Operation using a location not in flash. OutOfBounds, /// Unaligned operation or using unaligned buffers. Unaligned, diff --git a/embassy-nrf/src/twim.rs b/embassy-nrf/src/twim.rs index 9ae569609..cab36884f 100644 --- a/embassy-nrf/src/twim.rs +++ b/embassy-nrf/src/twim.rs @@ -336,7 +336,7 @@ impl<'d, T: Instance> Twim<'d, T> { return Poll::Ready(()); } - // stop if an error occured + // stop if an error occurred if r.events_error.read().bits() != 0 { r.events_error.reset(); r.tasks_stop.write(|w| unsafe { w.bits(1) }); diff --git a/embassy-nrf/src/twis.rs b/embassy-nrf/src/twis.rs index bfa30b044..f68a9940a 100644 --- a/embassy-nrf/src/twis.rs +++ b/embassy-nrf/src/twis.rs @@ -320,7 +320,7 @@ impl<'d, T: Instance> Twis<'d, T> { fn blocking_listen_wait_end(&mut self, status: Status) -> Result { let r = T::regs(); loop { - // stop if an error occured + // stop if an error occurred if r.events_error.read().bits() != 0 { r.events_error.reset(); r.tasks_stop.write(|w| unsafe { w.bits(1) }); @@ -346,7 +346,7 @@ impl<'d, T: Instance> Twis<'d, T> { fn blocking_wait(&mut self) -> Result { let r = T::regs(); loop { - // stop if an error occured + // stop if an error occurred if r.events_error.read().bits() != 0 { r.events_error.reset(); r.tasks_stop.write(|w| unsafe { w.bits(1) }); @@ -372,7 +372,7 @@ impl<'d, T: Instance> Twis<'d, T> { let r = T::regs(); let deadline = Instant::now() + timeout; loop { - // stop if an error occured + // stop if an error occurred if r.events_error.read().bits() != 0 { r.events_error.reset(); r.tasks_stop.write(|w| unsafe { w.bits(1) }); @@ -432,7 +432,7 @@ impl<'d, T: Instance> Twis<'d, T> { let r = T::regs(); let deadline = Instant::now() + timeout; loop { - // stop if an error occured + // stop if an error occurred if r.events_error.read().bits() != 0 { r.events_error.reset(); r.tasks_stop.write(|w| unsafe { w.bits(1) }); @@ -465,7 +465,7 @@ impl<'d, T: Instance> Twis<'d, T> { s.waker.register(cx.waker()); - // stop if an error occured + // stop if an error occurred if r.events_error.read().bits() != 0 { r.events_error.reset(); r.tasks_stop.write(|w| unsafe { w.bits(1) }); @@ -495,7 +495,7 @@ impl<'d, T: Instance> Twis<'d, T> { s.waker.register(cx.waker()); - // stop if an error occured + // stop if an error occurred if r.events_error.read().bits() != 0 { r.events_error.reset(); r.tasks_stop.write(|w| unsafe { w.bits(1) }); @@ -522,7 +522,7 @@ impl<'d, T: Instance> Twis<'d, T> { s.waker.register(cx.waker()); - // stop if an error occured + // stop if an error occurred if r.events_error.read().bits() != 0 { r.events_error.reset(); r.tasks_stop.write(|w| unsafe { w.bits(1) }); diff --git a/embassy-rp/src/flash.rs b/embassy-rp/src/flash.rs index 6ab05ff0b..51c7af913 100644 --- a/embassy-rp/src/flash.rs +++ b/embassy-rp/src/flash.rs @@ -25,7 +25,7 @@ pub const ERASE_SIZE: usize = 4096; #[derive(Debug, Copy, Clone, PartialEq, Eq)] #[cfg_attr(feature = "defmt", derive(defmt::Format))] pub enum Error { - /// Opration using a location not in flash. + /// Operation using a location not in flash. OutOfBounds, /// Unaligned operation or using unaligned buffers. Unaligned, diff --git a/embassy-rp/src/i2c.rs b/embassy-rp/src/i2c.rs index cd5364393..d5dc94406 100644 --- a/embassy-rp/src/i2c.rs +++ b/embassy-rp/src/i2c.rs @@ -551,7 +551,7 @@ impl<'d, T: Instance + 'd, M: Mode> I2c<'d, T, M> { if abort_reason.is_err() || (send_stop && last) { // If the transaction was aborted or if it completed - // successfully wait until the STOP condition has occured. + // successfully wait until the STOP condition has occurred. while !p.ic_raw_intr_stat().read().stop_det() {} diff --git a/embassy-rp/src/uart/buffered.rs b/embassy-rp/src/uart/buffered.rs index 59fec8f1b..9d3de1bd8 100644 --- a/embassy-rp/src/uart/buffered.rs +++ b/embassy-rp/src/uart/buffered.rs @@ -544,7 +544,7 @@ pub(crate) unsafe fn on_interrupt(_: *mut ()) { s.rx_waker.wake(); } // Disable any further RX interrupts when the buffer becomes full or - // errors have occured. this lets us buffer additional errors in the + // errors have occurred. This lets us buffer additional errors in the // fifo without needing more error storage locations, and most applications // will want to do a full reset of their uart state anyway once an error // has happened. diff --git a/embassy-rp/src/uart/mod.rs b/embassy-rp/src/uart/mod.rs index 4084c158a..a0ee6b4ce 100644 --- a/embassy-rp/src/uart/mod.rs +++ b/embassy-rp/src/uart/mod.rs @@ -231,7 +231,7 @@ impl<'d, T: Instance> UartTx<'d, T, Async> { } impl<'d, T: Instance, M: Mode> UartRx<'d, T, M> { - /// Create a new DMA-enabled UART which can only recieve data + /// Create a new DMA-enabled UART which can only receive data pub fn new( _uart: impl Peripheral

+ 'd, rx: impl Peripheral

> + 'd, @@ -690,7 +690,7 @@ impl<'d, T: Instance, M: Mode> Uart<'d, T, M> { self.tx.send_break(bits).await } - /// Split the Uart into a transmitter and receiver, which is particuarly + /// Split the Uart into a transmitter and receiver, which is particularly /// useful when having two tasks correlating to transmitting and receiving. pub fn split(self) -> (UartTx<'d, T, M>, UartRx<'d, T, M>) { (self.tx, self.rx) diff --git a/embassy-stm32/src/time_driver.rs b/embassy-stm32/src/time_driver.rs index 8e84570a4..d45c90dd8 100644 --- a/embassy-stm32/src/time_driver.rs +++ b/embassy-stm32/src/time_driver.rs @@ -250,7 +250,7 @@ impl RtcDriver { // Call after clearing alarm, so the callback can set another alarm. // safety: - // - we can ignore the possiblity of `f` being unset (null) because of the safety contract of `allocate_alarm`. + // - we can ignore the possibility of `f` being unset (null) because of the safety contract of `allocate_alarm`. // - other than that we only store valid function pointers into alarm.callback let f: fn(*mut ()) = unsafe { mem::transmute(alarm.callback.get()) }; f(alarm.ctx.get()); diff --git a/embassy-stm32/src/usart/mod.rs b/embassy-stm32/src/usart/mod.rs index dbce668c2..e946762af 100644 --- a/embassy-stm32/src/usart/mod.rs +++ b/embassy-stm32/src/usart/mod.rs @@ -112,7 +112,7 @@ pub struct UartRx<'d, T: BasicInstance, RxDma = NoDma> { } impl<'d, T: BasicInstance, TxDma> UartTx<'d, T, TxDma> { - /// usefull if you only want Uart Tx. It saves 1 pin and consumes a little less power + /// Useful if you only want Uart Tx. It saves 1 pin and consumes a little less power. pub fn new( peri: impl Peripheral

+ 'd, tx: impl Peripheral

> + 'd, @@ -210,7 +210,7 @@ impl<'d, T: BasicInstance, TxDma> UartTx<'d, T, TxDma> { } impl<'d, T: BasicInstance, RxDma> UartRx<'d, T, RxDma> { - /// usefull if you only want Uart Rx. It saves 1 pin and consumes a little less power + /// Useful if you only want Uart Rx. It saves 1 pin and consumes a little less power. pub fn new( peri: impl Peripheral

+ 'd, irq: impl Peripheral

+ 'd, @@ -757,7 +757,7 @@ impl<'d, T: BasicInstance, TxDma, RxDma> Uart<'d, T, TxDma, RxDma> { } /// Split the Uart into a transmitter and receiver, which is - /// particuarly useful when having two tasks correlating to + /// particularly useful when having two tasks correlating to /// transmitting and receiving. pub fn split(self) -> (UartTx<'d, T, TxDma>, UartRx<'d, T, RxDma>) { (self.tx, self.rx) diff --git a/embassy-usb-driver/src/lib.rs b/embassy-usb-driver/src/lib.rs index e8f71a2dc..2c05f94f7 100644 --- a/embassy-usb-driver/src/lib.rs +++ b/embassy-usb-driver/src/lib.rs @@ -97,7 +97,7 @@ impl EndpointAddress { } } -/// Infomation for an endpoint. +/// Information for an endpoint. #[derive(Copy, Clone, Eq, PartialEq, Debug)] #[cfg_attr(feature = "defmt", derive(defmt::Format))] pub struct EndpointInfo { diff --git a/embassy-usb/src/class/cdc_ncm/mod.rs b/embassy-usb/src/class/cdc_ncm/mod.rs index 262499ccb..d5556dd0b 100644 --- a/embassy-usb/src/class/cdc_ncm/mod.rs +++ b/embassy-usb/src/class/cdc_ncm/mod.rs @@ -370,7 +370,7 @@ pub struct Sender<'d, D: Driver<'d>> { impl<'d, D: Driver<'d>> Sender<'d, D> { /// Write a packet. /// - /// This waits until the packet is succesfully stored in the CDC-NCM endpoint buffers. + /// This waits until the packet is successfully stored in the CDC-NCM endpoint buffers. pub async fn write_packet(&mut self, data: &[u8]) -> Result<(), EndpointError> { let seq = self.seq; self.seq = self.seq.wrapping_add(1); @@ -436,7 +436,7 @@ pub struct Receiver<'d, D: Driver<'d>> { impl<'d, D: Driver<'d>> Receiver<'d, D> { /// Write a network packet. /// - /// This waits until a packet is succesfully received from the endpoint buffers. + /// This waits until a packet is successfully received from the endpoint buffers. pub async fn read_packet(&mut self, buf: &mut [u8]) -> Result { // Retry loop loop { diff --git a/embassy-usb/src/class/hid.rs b/embassy-usb/src/class/hid.rs index 03e4c1dbb..889d66ec5 100644 --- a/embassy-usb/src/class/hid.rs +++ b/embassy-usb/src/class/hid.rs @@ -165,7 +165,7 @@ impl<'d, D: Driver<'d>, const READ_N: usize, const WRITE_N: usize> HidReaderWrit } } - /// Splits into seperate readers/writers for input and output reports. + /// Splits into separate readers/writers for input and output reports. pub fn split(self) -> (HidReader<'d, D, READ_N>, HidWriter<'d, D, WRITE_N>) { (self.reader, self.writer) } diff --git a/embassy-usb/src/msos.rs b/embassy-usb/src/msos.rs index 218d9931a..187b2ff8e 100644 --- a/embassy-usb/src/msos.rs +++ b/embassy-usb/src/msos.rs @@ -186,7 +186,7 @@ impl<'d> MsOsDescriptorWriter<'d> { capability_type::PLATFORM, &[ 0, // reserved - // platform capability UUID, Microsoft OS 2.0 platform compabitility + // platform capability UUID, Microsoft OS 2.0 platform compatibility 0xdf, 0x60, 0xdd, diff --git a/examples/nrf52840/src/bin/pubsub.rs b/examples/nrf52840/src/bin/pubsub.rs index 688e6d075..cca60ebc9 100644 --- a/examples/nrf52840/src/bin/pubsub.rs +++ b/examples/nrf52840/src/bin/pubsub.rs @@ -74,9 +74,9 @@ async fn fast_logger(mut messages: Subscriber<'static, ThreadModeRawMutex, Messa } /// A logger task that awaits the messages, but also does some other work. -/// Because of this, depeding on how the messages were published, the subscriber might miss some messages +/// Because of this, depending on how the messages were published, the subscriber might miss some messages. /// -/// This takes the dynamic `DynSubscriber`. This is not as performant as the generic version, but let's you ignore some of the generics +/// This takes the dynamic `DynSubscriber`. This is not as performant as the generic version, but let's you ignore some of the generics. #[embassy_executor::task] async fn slow_logger(mut messages: DynSubscriber<'static, Message>) { loop { diff --git a/examples/nrf52840/src/bin/usb_serial.rs b/examples/nrf52840/src/bin/usb_serial.rs index 9727a4f57..dc95cde84 100644 --- a/examples/nrf52840/src/bin/usb_serial.rs +++ b/examples/nrf52840/src/bin/usb_serial.rs @@ -40,7 +40,7 @@ async fn main(_spawner: Spawner) { config.max_power = 100; config.max_packet_size_0 = 64; - // Required for windows compatiblity. + // 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; diff --git a/examples/nrf52840/src/bin/usb_serial_multitask.rs b/examples/nrf52840/src/bin/usb_serial_multitask.rs index 6da2c2a2f..ac22d9499 100644 --- a/examples/nrf52840/src/bin/usb_serial_multitask.rs +++ b/examples/nrf52840/src/bin/usb_serial_multitask.rs @@ -66,7 +66,7 @@ async fn main(spawner: Spawner) { config.max_power = 100; config.max_packet_size_0 = 64; - // Required for windows compatiblity. + // 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; diff --git a/examples/nrf52840/src/bin/usb_serial_winusb.rs b/examples/nrf52840/src/bin/usb_serial_winusb.rs index 6e4f71a48..1d39d3841 100644 --- a/examples/nrf52840/src/bin/usb_serial_winusb.rs +++ b/examples/nrf52840/src/bin/usb_serial_winusb.rs @@ -45,7 +45,7 @@ async fn main(_spawner: Spawner) { config.max_power = 100; config.max_packet_size_0 = 64; - // Required for windows compatiblity. + // 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; diff --git a/examples/rp/src/bin/usb_serial.rs b/examples/rp/src/bin/usb_serial.rs index a991082ee..8160a1875 100644 --- a/examples/rp/src/bin/usb_serial.rs +++ b/examples/rp/src/bin/usb_serial.rs @@ -30,7 +30,7 @@ async fn main(_spawner: Spawner) { config.max_power = 100; config.max_packet_size_0 = 64; - // Required for windows compatiblity. + // 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; diff --git a/examples/stm32f0/src/bin/button_controlled_blink.rs b/examples/stm32f0/src/bin/button_controlled_blink.rs index e1f223433..f362c53f5 100644 --- a/examples/stm32f0/src/bin/button_controlled_blink.rs +++ b/examples/stm32f0/src/bin/button_controlled_blink.rs @@ -17,8 +17,8 @@ static BLINK_MS: AtomicU32 = AtomicU32::new(0); #[embassy_executor::task] async fn led_task(led: AnyPin) { - // Configure the LED pin as a push pull ouput and obtain handler. - // On the Nucleo F091RC theres an on-board LED connected to pin PA5. + // Configure the LED pin as a push pull output and obtain handler. + // On the Nucleo F091RC there's an on-board LED connected to pin PA5. let mut led = Output::new(led, Level::Low, Speed::Low); loop { diff --git a/examples/stm32f4/src/bin/usb_serial.rs b/examples/stm32f4/src/bin/usb_serial.rs index baabc1a2d..d2b1dca43 100644 --- a/examples/stm32f4/src/bin/usb_serial.rs +++ b/examples/stm32f4/src/bin/usb_serial.rs @@ -34,7 +34,7 @@ async fn main(_spawner: Spawner) { config.product = Some("USB-serial example"); config.serial_number = Some("12345678"); - // Required for windows compatiblity. + // 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; diff --git a/examples/stm32f7/src/bin/usb_serial.rs b/examples/stm32f7/src/bin/usb_serial.rs index 5fd9d2ec9..dca90d9cb 100644 --- a/examples/stm32f7/src/bin/usb_serial.rs +++ b/examples/stm32f7/src/bin/usb_serial.rs @@ -35,7 +35,7 @@ async fn main(_spawner: Spawner) { config.product = Some("USB-serial example"); config.serial_number = Some("12345678"); - // Required for windows compatiblity. + // 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; diff --git a/examples/stm32h5/src/bin/usb_serial.rs b/examples/stm32h5/src/bin/usb_serial.rs index 6af269c1d..4f987cbd1 100644 --- a/examples/stm32h5/src/bin/usb_serial.rs +++ b/examples/stm32h5/src/bin/usb_serial.rs @@ -57,7 +57,7 @@ async fn main(_spawner: Spawner) { config.product = Some("USB-serial example"); config.serial_number = Some("12345678"); - // Required for windows compatiblity. + // 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; diff --git a/examples/stm32h7/src/bin/usb_serial.rs b/examples/stm32h7/src/bin/usb_serial.rs index 9ef520ae2..475af116d 100644 --- a/examples/stm32h7/src/bin/usb_serial.rs +++ b/examples/stm32h7/src/bin/usb_serial.rs @@ -34,7 +34,7 @@ async fn main(_spawner: Spawner) { config.product = Some("USB-serial example"); config.serial_number = Some("12345678"); - // Required for windows compatiblity. + // 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; diff --git a/examples/stm32l4/src/bin/usb_serial.rs b/examples/stm32l4/src/bin/usb_serial.rs index 663f60d52..bdb290e63 100644 --- a/examples/stm32l4/src/bin/usb_serial.rs +++ b/examples/stm32l4/src/bin/usb_serial.rs @@ -36,7 +36,7 @@ async fn main(_spawner: Spawner) { config.product = Some("USB-serial example"); config.serial_number = Some("12345678"); - // Required for windows compatiblity. + // 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; diff --git a/examples/stm32u5/src/bin/usb_serial.rs b/examples/stm32u5/src/bin/usb_serial.rs index 8cd3bf2f4..4882cd2e0 100644 --- a/examples/stm32u5/src/bin/usb_serial.rs +++ b/examples/stm32u5/src/bin/usb_serial.rs @@ -36,7 +36,7 @@ async fn main(_spawner: Spawner) { config.product = Some("USB-serial example"); config.serial_number = Some("12345678"); - // Required for windows compatiblity. + // 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; diff --git a/examples/stm32wl/src/bin/uart_async.rs b/examples/stm32wl/src/bin/uart_async.rs index f12fec4c8..ac8766af6 100644 --- a/examples/stm32wl/src/bin/uart_async.rs +++ b/examples/stm32wl/src/bin/uart_async.rs @@ -48,7 +48,7 @@ async fn main(_spawner: Spawner) { //Write suc. } Err(..) => { - //Wasnt able to write + //Wasn't able to write } } } From 5df263db38c593ca6946a854c4b53e6224285332 Mon Sep 17 00:00:00 2001 From: Dirk Stolle Date: Mon, 8 May 2023 23:28:01 +0200 Subject: [PATCH 5/6] Update GitHub Actions CI The following updates are performed: * update actions/cache to v3 * update actions/checkout to v3 --- .github/workflows/doc.yml | 2 +- .github/workflows/rust.yml | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/.github/workflows/doc.yml b/.github/workflows/doc.yml index 411b7589f..b4e225e64 100644 --- a/.github/workflows/doc.yml +++ b/.github/workflows/doc.yml @@ -29,7 +29,7 @@ jobs: concurrency: doc-${{ matrix.crates }} steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v3 with: submodules: true - name: Install Rust targets diff --git a/.github/workflows/rust.yml b/.github/workflows/rust.yml index 79354fe70..47dc8fd7a 100644 --- a/.github/workflows/rust.yml +++ b/.github/workflows/rust.yml @@ -22,11 +22,11 @@ jobs: id-token: write contents: read steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v3 with: submodules: true - name: Cache multiple paths - uses: actions/cache@v2 + uses: actions/cache@v3 with: path: | ~/.cargo/bin/ @@ -44,11 +44,11 @@ jobs: build-stable: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v3 with: submodules: true - name: Cache multiple paths - uses: actions/cache@v2 + uses: actions/cache@v3 with: path: | ~/.cargo/bin/ @@ -67,7 +67,7 @@ jobs: test: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v3 - name: Test boot working-directory: ./embassy-boot/boot From 0e3cd87a323c464842ea66eeaf7b6da00d70d300 Mon Sep 17 00:00:00 2001 From: pennae Date: Tue, 9 May 2023 18:36:17 +0200 Subject: [PATCH 6/6] rp: use rp2040-boot2 to provide the boot2 blob we're currently shipping an old boot2 that runs the flash at half speed. use the more recent version instead, and allow user to choose between the different supported boot2 versions for different flash chips if they need that. --- embassy-rp/Cargo.toml | 10 ++++++++++ embassy-rp/src/boot2.bin | Bin 256 -> 0 bytes embassy-rp/src/lib.rs | 29 ++++++++++++++++++++++++++--- 3 files changed, 36 insertions(+), 3 deletions(-) delete mode 100644 embassy-rp/src/boot2.bin diff --git a/embassy-rp/Cargo.toml b/embassy-rp/Cargo.toml index 59d0bf338..28a35a1bd 100644 --- a/embassy-rp/Cargo.toml +++ b/embassy-rp/Cargo.toml @@ -30,6 +30,15 @@ rom-func-cache = [] intrinsics = [] rom-v2-intrinsics = [] +# boot2 flash chip support. if none of these is enabled we'll default to w25q080 (used on the pico) +boot2-at25sf128a = [] +boot2-gd25q64cs = [] +boot2-generic-03h = [] +boot2-is25lp080 = [] +boot2-ram-memcpy = [] +boot2-w25q080 = [] +boot2-w25x10cl = [] + # Enable nightly-only features nightly = ["embassy-executor/nightly", "embedded-hal-1", "embedded-hal-async", "embassy-embedded-hal/nightly", "dep:embassy-usb-driver", "dep:embedded-io"] @@ -71,3 +80,4 @@ embedded-hal-nb = { version = "=1.0.0-alpha.2", optional = true} paste = "1.0" pio-proc = {version= "0.2" } pio = {version= "0.2.1" } +rp2040-boot2 = "0.3" diff --git a/embassy-rp/src/boot2.bin b/embassy-rp/src/boot2.bin deleted file mode 100644 index fdc1fc756b0e876b93b99f5475bea32902b13656..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 256 zcmZSBYUHh`5Rot=gGsT&c}BvG1c}6mL_Kc?#hD2#ijj$oiXW6_255UqCNKg;OcfYD zxcp#Jn&2dIflW~|jp2jI56L`65KBQKO$x}@0rEkR6{u4G2csf~)6a__v!sD0FepYQ zNO?+oFoMl`4b-&&Y=+PekP0zR5vUB~9tI7D3k>c;9>Sg+3Ct%NK67+%xHE5^nZ=^O z==A#nBar-Yk$ErER*5u;wEy2f{g=p-$Ya{ez`*3dz`!8Ez`)MHz#Pw@sKmhV1;|%Y XU|7Jw$RNP+mf-z53y?sZ3 diff --git a/embassy-rp/src/lib.rs b/embassy-rp/src/lib.rs index cba7559df..99f62738d 100644 --- a/embassy-rp/src/lib.rs +++ b/embassy-rp/src/lib.rs @@ -131,9 +131,32 @@ embassy_hal_common::peripherals! { WATCHDOG, } -#[link_section = ".boot2"] -#[used] -static BOOT2: [u8; 256] = *include_bytes!("boot2.bin"); +macro_rules! select_bootloader { + ( $( $feature:literal => $loader:ident, )+ default => $default:ident ) => { + $( + #[cfg(feature = $feature)] + #[link_section = ".boot2"] + #[used] + static BOOT2: [u8; 256] = rp2040_boot2::$loader; + )* + + #[cfg(not(any( $( feature = $feature),* )))] + #[link_section = ".boot2"] + #[used] + static BOOT2: [u8; 256] = rp2040_boot2::$default; + } +} + +select_bootloader! { + "boot2-at25sf128a" => BOOT_LOADER_AT25SF128A, + "boot2-gd25q64cs" => BOOT_LOADER_GD25Q64CS, + "boot2-generic-03h" => BOOT_LOADER_GENERIC_03H, + "boot2-is25lp080" => BOOT_LOADER_IS25LP080, + "boot2-ram-memcpy" => BOOT_LOADER_RAM_MEMCPY, + "boot2-w25q080" => BOOT_LOADER_W25Q080, + "boot2-w25x10cl" => BOOT_LOADER_W25X10CL, + default => BOOT_LOADER_W25Q080 +} pub mod config { #[non_exhaustive]