+ 'd,
@@ -143,6 +146,7 @@ where
}
}
+ /// Write data to peripheral and return status.
pub async fn write(&mut self, write: &[u32]) -> u32 {
self.sm.set_enable(false);
let write_bits = write.len() * 32 - 1;
@@ -152,10 +156,10 @@ where
defmt::trace!("write={} read={}", write_bits, read_bits);
unsafe {
- pio_instr_util::set_x(&mut self.sm, write_bits as u32);
- pio_instr_util::set_y(&mut self.sm, read_bits as u32);
- pio_instr_util::set_pindir(&mut self.sm, 0b1);
- pio_instr_util::exec_jmp(&mut self.sm, self.wrap_target);
+ instr::set_x(&mut self.sm, write_bits as u32);
+ instr::set_y(&mut self.sm, read_bits as u32);
+ instr::set_pindir(&mut self.sm, 0b1);
+ instr::exec_jmp(&mut self.sm, self.wrap_target);
}
self.sm.set_enable(true);
@@ -170,6 +174,7 @@ where
status
}
+ /// Send command and read response into buffer.
pub async fn cmd_read(&mut self, cmd: u32, read: &mut [u32]) -> u32 {
self.sm.set_enable(false);
let write_bits = 31;
@@ -179,10 +184,10 @@ where
defmt::trace!("write={} read={}", write_bits, read_bits);
unsafe {
- pio_instr_util::set_y(&mut self.sm, read_bits as u32);
- pio_instr_util::set_x(&mut self.sm, write_bits as u32);
- pio_instr_util::set_pindir(&mut self.sm, 0b1);
- pio_instr_util::exec_jmp(&mut self.sm, self.wrap_target);
+ instr::set_y(&mut self.sm, read_bits as u32);
+ instr::set_x(&mut self.sm, write_bits as u32);
+ instr::set_pindir(&mut self.sm, 0b1);
+ instr::exec_jmp(&mut self.sm, self.wrap_target);
}
// self.cs.set_low();
@@ -200,9 +205,8 @@ where
}
}
-impl<'d, CS, PIO, const SM: usize, DMA> SpiBusCyw43 for PioSpi<'d, CS, PIO, SM, DMA>
+impl<'d, PIO, const SM: usize, DMA> SpiBusCyw43 for PioSpi<'d, PIO, SM, DMA>
where
- CS: Pin,
PIO: Instance,
DMA: Channel,
{
diff --git a/cyw43/Cargo.toml b/cyw43/Cargo.toml
index 293c00982..f279739e4 100644
--- a/cyw43/Cargo.toml
+++ b/cyw43/Cargo.toml
@@ -2,16 +2,22 @@
name = "cyw43"
version = "0.1.0"
edition = "2021"
+description = "Rust driver for the CYW43439 WiFi chip, used in the Raspberry Pi Pico W."
+keywords = ["embedded", "cyw43", "embassy-net", "embedded-hal-async", "wifi"]
+categories = ["embedded", "hardware-support", "no-std", "network-programming", "asynchronous"]
+license = "MIT OR Apache-2.0"
+repository = "https://github.com/embassy-rs/embassy"
+documentation = "https://docs.embassy.dev/cyw43"
[features]
-defmt = ["dep:defmt"]
+defmt = ["dep:defmt", "heapless/defmt-03", "embassy-time/defmt"]
log = ["dep:log"]
# Fetch console logs from the WiFi firmware and forward them to `log` or `defmt`.
firmware-logs = []
[dependencies]
-embassy-time = { version = "0.2", path = "../embassy-time"}
+embassy-time = { version = "0.3.0", path = "../embassy-time"}
embassy-sync = { version = "0.5.0", path = "../embassy-sync"}
embassy-futures = { version = "0.1.0", path = "../embassy-futures"}
embassy-net-driver-channel = { version = "0.2.0", path = "../embassy-net-driver-channel"}
@@ -23,11 +29,16 @@ cortex-m = "0.7.6"
cortex-m-rt = "0.7.0"
futures = { version = "0.3.17", default-features = false, features = ["async-await", "cfg-target-has-atomic", "unstable"] }
-embedded-hal-1 = { package = "embedded-hal", version = "1.0.0-rc.2" }
+embedded-hal-1 = { package = "embedded-hal", version = "1.0" }
num_enum = { version = "0.5.7", default-features = false }
+heapless = "0.8.0"
+
[package.metadata.embassy_docs]
src_base = "https://github.com/embassy-rs/embassy/blob/cyw43-v$VERSION/cyw43/src/"
src_base_git = "https://github.com/embassy-rs/embassy/blob/$COMMIT/cyw43/src/"
target = "thumbv6m-none-eabi"
features = ["defmt", "firmware-logs"]
+
+[package.metadata.docs.rs]
+features = ["defmt", "firmware-logs"]
diff --git a/cyw43/README.md b/cyw43/README.md
index 5b8f3cf40..dabdf0471 100644
--- a/cyw43/README.md
+++ b/cyw43/README.md
@@ -44,14 +44,3 @@ This example implements a TCP echo server on port 1234. You can try connecting t
nc 192.168.0.250 1234
```
Send it some data, you should see it echoed back and printed in the firmware's logs.
-
-## License
-
-This work is licensed under either of
-
-- Apache License, Version 2.0 ([LICENSE-APACHE](LICENSE-APACHE) or
- )
-- MIT license ([LICENSE-MIT](LICENSE-MIT) or )
-
-at your option.
-
diff --git a/cyw43/src/control.rs b/cyw43/src/control.rs
index 826edfe1a..135b8c245 100644
--- a/cyw43/src/control.rs
+++ b/cyw43/src/control.rs
@@ -3,7 +3,7 @@ use core::iter::zip;
use embassy_net_driver_channel as ch;
use embassy_net_driver_channel::driver::{HardwareAddress, LinkState};
-use embassy_time::Timer;
+use embassy_time::{Duration, Timer};
use crate::consts::*;
use crate::events::{Event, EventSubscriber, Events};
@@ -12,23 +12,66 @@ use crate::ioctl::{IoctlState, IoctlType};
use crate::structs::*;
use crate::{countries, events, PowerManagementMode};
+/// Control errors.
#[derive(Debug)]
pub struct Error {
+ /// Status code.
pub status: u32,
}
+/// Multicast errors.
#[derive(Debug)]
pub enum AddMulticastAddressError {
+ /// Not a multicast address.
NotMulticast,
+ /// No free address slots.
NoFreeSlots,
}
+/// Control driver.
pub struct Control<'a> {
state_ch: ch::StateRunner<'a>,
events: &'a Events,
ioctl_state: &'a IoctlState,
}
+#[derive(Copy, Clone)]
+#[cfg_attr(feature = "defmt", derive(defmt::Format))]
+pub enum ScanType {
+ Active,
+ Passive,
+}
+
+#[derive(Clone)]
+#[cfg_attr(feature = "defmt", derive(defmt::Format))]
+pub struct ScanOptions {
+ pub ssid: Option>,
+ /// If set to `None`, all APs will be returned. If set to `Some`, only APs
+ /// with the specified BSSID will be returned.
+ pub bssid: Option<[u8; 6]>,
+ /// Number of probes to send on each channel.
+ pub nprobes: Option,
+ /// Time to spend waiting on the home channel.
+ pub home_time: Option,
+ /// Scan type: active or passive.
+ pub scan_type: ScanType,
+ /// Period of time to wait on each channel when passive scanning.
+ pub dwell_time: Option,
+}
+
+impl Default for ScanOptions {
+ fn default() -> Self {
+ Self {
+ ssid: None,
+ bssid: None,
+ nprobes: None,
+ home_time: None,
+ scan_type: ScanType::Passive,
+ dwell_time: None,
+ }
+ }
+}
+
impl<'a> Control<'a> {
pub(crate) fn new(state_ch: ch::StateRunner<'a>, event_sub: &'a Events, ioctl_state: &'a IoctlState) -> Self {
Self {
@@ -38,6 +81,7 @@ impl<'a> Control<'a> {
}
}
+ /// Initialize WiFi controller.
pub async fn init(&mut self, clm: &[u8]) {
const CHUNK_SIZE: usize = 1024;
@@ -154,6 +198,7 @@ impl<'a> Control<'a> {
self.ioctl(IoctlType::Set, IOCTL_CMD_DOWN, 0, &mut []).await;
}
+ /// Set power management mode.
pub async fn set_power_management(&mut self, mode: PowerManagementMode) {
// power save mode
let mode_num = mode.mode();
@@ -166,6 +211,7 @@ impl<'a> Control<'a> {
self.ioctl_set_u32(86, 0, mode_num).await;
}
+ /// Join an unprotected network with the provided ssid.
pub async fn join_open(&mut self, ssid: &str) -> Result<(), Error> {
self.set_iovar_u32("ampdu_ba_wsize", 8).await;
@@ -183,6 +229,7 @@ impl<'a> Control<'a> {
self.wait_for_join(i).await
}
+ /// Join an protected network with the provided ssid and passphrase.
pub async fn join_wpa2(&mut self, ssid: &str, passphrase: &str) -> Result<(), Error> {
self.set_iovar_u32("ampdu_ba_wsize", 8).await;
@@ -250,16 +297,19 @@ impl<'a> Control<'a> {
}
}
+ /// Set GPIO pin on WiFi chip.
pub async fn gpio_set(&mut self, gpio_n: u8, gpio_en: bool) {
assert!(gpio_n < 3);
self.set_iovar_u32x2("gpioout", 1 << gpio_n, if gpio_en { 1 << gpio_n } else { 0 })
.await
}
+ /// Start open access point.
pub async fn start_ap_open(&mut self, ssid: &str, channel: u8) {
self.start_ap(ssid, "", Security::OPEN, channel).await;
}
+ /// Start WPA2 protected access point.
pub async fn start_ap_wpa2(&mut self, ssid: &str, passphrase: &str, channel: u8) {
self.start_ap(ssid, passphrase, Security::WPA2_AES_PSK, channel).await;
}
@@ -458,22 +508,54 @@ impl<'a> Control<'a> {
/// # Note
/// Device events are currently implemented using a bounded queue.
/// To not miss any events, you should make sure to always await the stream.
- pub async fn scan(&mut self) -> Scanner<'_> {
+ pub async fn scan(&mut self, scan_opts: ScanOptions) -> Scanner<'_> {
+ const SCANTYPE_ACTIVE: u8 = 0;
const SCANTYPE_PASSIVE: u8 = 1;
+ let dwell_time = match scan_opts.dwell_time {
+ None => !0,
+ Some(t) => {
+ let mut t = t.as_millis() as u32;
+ if t == !0 {
+ t = !0 - 1;
+ }
+ t
+ }
+ };
+
+ let mut active_time = !0;
+ let mut passive_time = !0;
+ let scan_type = match scan_opts.scan_type {
+ ScanType::Active => {
+ active_time = dwell_time;
+ SCANTYPE_ACTIVE
+ }
+ ScanType::Passive => {
+ passive_time = dwell_time;
+ SCANTYPE_PASSIVE
+ }
+ };
+
let scan_params = ScanParams {
version: 1,
action: 1,
sync_id: 1,
- ssid_len: 0,
- ssid: [0; 32],
- bssid: [0xff; 6],
+ ssid_len: scan_opts.ssid.as_ref().map(|e| e.as_bytes().len() as u32).unwrap_or(0),
+ ssid: scan_opts
+ .ssid
+ .map(|e| {
+ let mut ssid = [0; 32];
+ ssid[..e.as_bytes().len()].copy_from_slice(e.as_bytes());
+ ssid
+ })
+ .unwrap_or([0; 32]),
+ bssid: scan_opts.bssid.unwrap_or([0xff; 6]),
bss_type: 2,
- scan_type: SCANTYPE_PASSIVE,
- nprobes: !0,
- active_time: !0,
- passive_time: !0,
- home_time: !0,
+ scan_type,
+ nprobes: scan_opts.nprobes.unwrap_or(!0).into(),
+ active_time,
+ passive_time,
+ home_time: scan_opts.home_time.map(|e| e.as_millis() as u32).unwrap_or(!0),
channel_num: 0,
channel_list: [0; 1],
};
@@ -494,13 +576,14 @@ impl<'a> Control<'a> {
}
}
+/// WiFi network scanner.
pub struct Scanner<'a> {
subscriber: EventSubscriber<'a>,
events: &'a Events,
}
impl Scanner<'_> {
- /// wait for the next found network
+ /// Wait for the next found network.
pub async fn next(&mut self) -> Option {
let event = self.subscriber.next_message_pure().await;
if event.header.status != EStatus::PARTIAL {
diff --git a/cyw43/src/events.rs b/cyw43/src/events.rs
index a94c49a0c..44bfa98e9 100644
--- a/cyw43/src/events.rs
+++ b/cyw43/src/events.rs
@@ -311,13 +311,13 @@ pub struct Status {
pub status: u32,
}
-#[derive(Clone, Copy)]
+#[derive(Copy, Clone)]
pub enum Payload {
None,
BssInfo(BssInfo),
}
-#[derive(Clone, Copy)]
+#[derive(Copy, Clone)]
pub struct Message {
pub header: Status,
diff --git a/cyw43/src/fmt.rs b/cyw43/src/fmt.rs
index 78e583c1c..2ac42c557 100644
--- a/cyw43/src/fmt.rs
+++ b/cyw43/src/fmt.rs
@@ -1,5 +1,5 @@
#![macro_use]
-#![allow(unused_macros)]
+#![allow(unused)]
use core::fmt::{Debug, Display, LowerHex};
@@ -229,7 +229,6 @@ impl Try for Result {
}
}
-#[allow(unused)]
pub(crate) struct Bytes<'a>(pub &'a [u8]);
impl<'a> Debug for Bytes<'a> {
diff --git a/cyw43/src/lib.rs b/cyw43/src/lib.rs
index 300465e36..19b0cb194 100644
--- a/cyw43/src/lib.rs
+++ b/cyw43/src/lib.rs
@@ -2,6 +2,8 @@
#![no_main]
#![allow(async_fn_in_trait)]
#![deny(unused_must_use)]
+#![doc = include_str!("../README.md")]
+#![warn(missing_docs)]
// This mod MUST go first, so that the others see its macros.
pub(crate) mod fmt;
@@ -102,6 +104,7 @@ const CHIP: Chip = Chip {
chanspec_ctl_sb_mask: 0x0700,
};
+/// Driver state.
pub struct State {
ioctl_state: IoctlState,
ch: ch::State,
@@ -109,6 +112,7 @@ pub struct State {
}
impl State {
+ /// Create new driver state holder.
pub fn new() -> Self {
Self {
ioctl_state: IoctlState::new(),
@@ -118,6 +122,7 @@ impl State {
}
}
+/// Power management modes.
#[derive(Debug, Clone, Copy, PartialEq, Eq)]
pub enum PowerManagementMode {
/// Custom, officially unsupported mode. Use at your own risk.
@@ -203,8 +208,13 @@ impl PowerManagementMode {
}
}
+/// Embassy-net driver.
pub type NetDriver<'a> = ch::Device<'a, MTU>;
+/// Create a new instance of the CYW43 driver.
+///
+/// Returns a handle to the network device, control handle and a runner for driving the low level
+/// stack.
pub async fn new<'a, PWR, SPI>(
state: &'a mut State,
pwr: PWR,
diff --git a/cyw43/src/runner.rs b/cyw43/src/runner.rs
index 83aee6b40..c72cf0def 100644
--- a/cyw43/src/runner.rs
+++ b/cyw43/src/runner.rs
@@ -34,6 +34,7 @@ impl Default for LogState {
}
}
+/// Driver communicating with the WiFi chip.
pub struct Runner<'a, PWR, SPI> {
ch: ch::Runner<'a, MTU>,
bus: Bus,
@@ -222,6 +223,7 @@ where
}
}
+ /// Run the
pub async fn run(mut self) -> ! {
let mut buf = [0; 512];
loop {
@@ -240,13 +242,12 @@ where
cmd,
iface,
}) => {
- self.send_ioctl(kind, cmd, iface, unsafe { &*iobuf }).await;
+ self.send_ioctl(kind, cmd, iface, unsafe { &*iobuf }, &mut buf).await;
self.check_status(&mut buf).await;
}
Either3::Second(packet) => {
trace!("tx pkt {:02x}", Bytes(&packet[..packet.len().min(48)]));
- let mut buf = [0; 512];
let buf8 = slice8_mut(&mut buf);
// There MUST be 2 bytes of padding between the SDPCM and BDC headers.
@@ -478,9 +479,8 @@ where
self.sdpcm_seq != self.sdpcm_seq_max && self.sdpcm_seq_max.wrapping_sub(self.sdpcm_seq) & 0x80 == 0
}
- async fn send_ioctl(&mut self, kind: IoctlType, cmd: u32, iface: u32, data: &[u8]) {
- let mut buf = [0; 512];
- let buf8 = slice8_mut(&mut buf);
+ async fn send_ioctl(&mut self, kind: IoctlType, cmd: u32, iface: u32, data: &[u8], buf: &mut [u32; 512]) {
+ let buf8 = slice8_mut(buf);
let total_len = SdpcmHeader::SIZE + CdcHeader::SIZE + data.len();
diff --git a/cyw43/src/structs.rs b/cyw43/src/structs.rs
index 5ba633c74..ae7ef6038 100644
--- a/cyw43/src/structs.rs
+++ b/cyw43/src/structs.rs
@@ -4,13 +4,16 @@ use crate::fmt::Bytes;
macro_rules! impl_bytes {
($t:ident) => {
impl $t {
+ /// Bytes consumed by this type.
pub const SIZE: usize = core::mem::size_of::();
+ /// Convert to byte array.
#[allow(unused)]
pub fn to_bytes(&self) -> [u8; Self::SIZE] {
unsafe { core::mem::transmute(*self) }
}
+ /// Create from byte array.
#[allow(unused)]
pub fn from_bytes(bytes: &[u8; Self::SIZE]) -> &Self {
let alignment = core::mem::align_of::();
@@ -23,6 +26,7 @@ macro_rules! impl_bytes {
unsafe { core::mem::transmute(bytes) }
}
+ /// Create from mutable byte array.
#[allow(unused)]
pub fn from_bytes_mut(bytes: &mut [u8; Self::SIZE]) -> &mut Self {
let alignment = core::mem::align_of::();
@@ -204,6 +208,7 @@ pub struct EthernetHeader {
}
impl EthernetHeader {
+ /// Swap endianness.
pub fn byteswap(&mut self) {
self.ether_type = self.ether_type.to_be();
}
@@ -472,19 +477,64 @@ impl ScanResults {
#[repr(C, packed(2))]
#[non_exhaustive]
pub struct BssInfo {
+ /// Version.
pub version: u32,
+ /// Length.
pub length: u32,
+ /// BSSID.
pub bssid: [u8; 6],
+ /// Beacon period.
pub beacon_period: u16,
+ /// Capability.
pub capability: u16,
+ /// SSID length.
pub ssid_len: u8,
+ /// SSID.
pub ssid: [u8; 32],
+ reserved1: [u8; 1],
+ /// Number of rates in the rates field.
+ pub rateset_count: u32,
+ /// Rates in 500kpbs units.
+ pub rates: [u8; 16],
+ /// Channel specification.
+ pub chanspec: u16,
+ /// Announcement traffic indication message.
+ pub atim_window: u16,
+ /// Delivery traffic indication message.
+ pub dtim_period: u8,
+ reserved2: [u8; 1],
+ /// Receive signal strength (in dbM).
+ pub rssi: i16,
+ /// Received noise (in dbM).
+ pub phy_noise: i8,
+ /// 802.11n capability.
+ pub n_cap: u8,
+ reserved3: [u8; 2],
+ /// 802.11n BSS capabilities.
+ pub nbss_cap: u32,
+ /// 802.11n control channel number.
+ pub ctl_ch: u8,
+ reserved4: [u8; 3],
+ reserved32: [u32; 1],
+ /// Flags.
+ pub flags: u8,
+ /// VHT capability.
+ pub vht_cap: u8,
+ reserved5: [u8; 2],
+ /// 802.11n BSS required MCS.
+ pub basic_mcs: [u8; 16],
+ /// Information Elements (IE) offset.
+ pub ie_offset: u16,
+ /// Length of Information Elements (IE) in bytes.
+ pub ie_length: u32,
+ /// Average signal-to-noise (SNR) ratio during frame reception.
+ pub snr: i16,
// there will be more stuff here
}
impl_bytes!(BssInfo);
impl BssInfo {
- pub fn parse(packet: &mut [u8]) -> Option<&mut Self> {
+ pub(crate) fn parse(packet: &mut [u8]) -> Option<&mut Self> {
if packet.len() < BssInfo::SIZE {
return None;
}
diff --git a/docs/README.md b/docs/README.md
new file mode 100644
index 000000000..0bf3a6c89
--- /dev/null
+++ b/docs/README.md
@@ -0,0 +1,4 @@
+# embassy docs
+
+The documentation hosted at [https://embassy.dev/book](https://embassy.dev/book). Building the documentation requires
+cloning the [embassy-book](https://github.com/embassy-rs/embassy-book) repository and following the instructions.
diff --git a/docs/modules/ROOT/examples/basic/Cargo.toml b/docs/modules/ROOT/examples/basic/Cargo.toml
index 8f6e05fae..2c282145d 100644
--- a/docs/modules/ROOT/examples/basic/Cargo.toml
+++ b/docs/modules/ROOT/examples/basic/Cargo.toml
@@ -6,8 +6,8 @@ version = "0.1.0"
license = "MIT OR Apache-2.0"
[dependencies]
-embassy-executor = { version = "0.4.0", path = "../../../../../embassy-executor", features = ["defmt", "integrated-timers", "arch-cortex-m", "executor-thread"] }
-embassy-time = { version = "0.2.0", path = "../../../../../embassy-time", features = ["defmt"] }
+embassy-executor = { version = "0.5.0", path = "../../../../../embassy-executor", features = ["defmt", "integrated-timers", "arch-cortex-m", "executor-thread"] }
+embassy-time = { version = "0.3.0", path = "../../../../../embassy-time", features = ["defmt"] }
embassy-nrf = { version = "0.1.0", path = "../../../../../embassy-nrf", features = ["defmt", "nrf52840", "time-driver-rtc1", "gpiote"] }
defmt = "0.3"
diff --git a/docs/modules/ROOT/examples/basic/src/main.rs b/docs/modules/ROOT/examples/basic/src/main.rs
index 04170db55..4412712c8 100644
--- a/docs/modules/ROOT/examples/basic/src/main.rs
+++ b/docs/modules/ROOT/examples/basic/src/main.rs
@@ -1,16 +1,14 @@
#![no_std]
#![no_main]
-#![feature(type_alias_impl_trait)]
use defmt::*;
use embassy_executor::Spawner;
use embassy_nrf::gpio::{Level, Output, OutputDrive};
-use embassy_nrf::peripherals::P0_13;
use embassy_time::{Duration, Timer};
use {defmt_rtt as _, panic_probe as _}; // global logger
#[embassy_executor::task]
-async fn blinker(mut led: Output<'static, P0_13>, interval: Duration) {
+async fn blinker(mut led: Output<'static>, interval: Duration) {
loop {
led.set_high();
Timer::after(interval).await;
diff --git a/docs/modules/ROOT/examples/layer-by-layer/blinky-async/Cargo.toml b/docs/modules/ROOT/examples/layer-by-layer/blinky-async/Cargo.toml
index dcdb71e7b..64f7e8403 100644
--- a/docs/modules/ROOT/examples/layer-by-layer/blinky-async/Cargo.toml
+++ b/docs/modules/ROOT/examples/layer-by-layer/blinky-async/Cargo.toml
@@ -8,7 +8,7 @@ license = "MIT OR Apache-2.0"
cortex-m = "0.7"
cortex-m-rt = "0.7"
embassy-stm32 = { version = "0.1.0", features = ["stm32l475vg", "memory-x", "exti"] }
-embassy-executor = { version = "0.4.0", features = ["nightly", "arch-cortex-m", "executor-thread"] }
+embassy-executor = { version = "0.5.0", features = ["arch-cortex-m", "executor-thread"] }
defmt = "0.3.0"
defmt-rtt = "0.3.0"
diff --git a/docs/modules/ROOT/examples/layer-by-layer/blinky-async/src/main.rs b/docs/modules/ROOT/examples/layer-by-layer/blinky-async/src/main.rs
index 8df632240..004602816 100644
--- a/docs/modules/ROOT/examples/layer-by-layer/blinky-async/src/main.rs
+++ b/docs/modules/ROOT/examples/layer-by-layer/blinky-async/src/main.rs
@@ -1,17 +1,16 @@
#![no_std]
#![no_main]
-#![feature(type_alias_impl_trait)]
use embassy_executor::Spawner;
use embassy_stm32::exti::ExtiInput;
-use embassy_stm32::gpio::{Input, Level, Output, Pull, Speed};
+use embassy_stm32::gpio::{Level, Output, Pull, Speed};
use {defmt_rtt as _, panic_probe as _};
#[embassy_executor::main]
async fn main(_spawner: Spawner) {
let p = embassy_stm32::init(Default::default());
let mut led = Output::new(p.PB14, Level::Low, Speed::VeryHigh);
- let mut button = ExtiInput::new(Input::new(p.PC13, Pull::Up), p.EXTI13);
+ let mut button = ExtiInput::new(p.PC13, p.EXTI13, Pull::Up);
loop {
button.wait_for_any_edge().await;
diff --git a/docs/modules/ROOT/examples/layer-by-layer/blinky-irq/src/main.rs b/docs/modules/ROOT/examples/layer-by-layer/blinky-irq/src/main.rs
index aecba0755..743c9d99b 100644
--- a/docs/modules/ROOT/examples/layer-by-layer/blinky-irq/src/main.rs
+++ b/docs/modules/ROOT/examples/layer-by-layer/blinky-irq/src/main.rs
@@ -6,13 +6,12 @@ use core::cell::RefCell;
use cortex_m::interrupt::Mutex;
use cortex_m::peripheral::NVIC;
use cortex_m_rt::entry;
-use embassy_stm32::gpio::{Input, Level, Output, Pin, Pull, Speed};
-use embassy_stm32::peripherals::{PB14, PC13};
+use embassy_stm32::gpio::{Input, Level, Output, Pull, Speed};
use embassy_stm32::{interrupt, pac};
use {defmt_rtt as _, panic_probe as _};
-static BUTTON: Mutex>>> = Mutex::new(RefCell::new(None));
-static LED: Mutex>>> = Mutex::new(RefCell::new(None));
+static BUTTON: Mutex>>> = Mutex::new(RefCell::new(None));
+static LED: Mutex>>> = Mutex::new(RefCell::new(None));
#[entry]
fn main() -> ! {
@@ -62,14 +61,14 @@ fn EXTI15_10() {
const PORT: u8 = 2;
const PIN: usize = 13;
-fn check_interrupt(_pin: &mut Input<'static, P>) -> bool {
+fn check_interrupt(_pin: &mut Input<'static>) -> bool {
let exti = pac::EXTI;
let pin = PIN;
let lines = exti.pr(0).read();
lines.line(pin)
}
-fn clear_interrupt(_pin: &mut Input<'static, P>) {
+fn clear_interrupt(_pin: &mut Input<'static>) {
let exti = pac::EXTI;
let pin = PIN;
let mut lines = exti.pr(0).read();
@@ -77,7 +76,7 @@ fn clear_interrupt(_pin: &mut Input<'static, P>) {
exti.pr(0).write_value(lines);
}
-fn enable_interrupt(_pin: &mut Input<'static, P>) {
+fn enable_interrupt(_pin: &mut Input<'static>) {
cortex_m::interrupt::free(|_| {
let rcc = pac::RCC;
rcc.apb2enr().modify(|w| w.set_syscfgen(true));
diff --git a/docs/modules/ROOT/nav.adoc b/docs/modules/ROOT/nav.adoc
index fabb80e31..44b0eddb9 100644
--- a/docs/modules/ROOT/nav.adoc
+++ b/docs/modules/ROOT/nav.adoc
@@ -3,10 +3,11 @@
** xref:project_structure.adoc[Project Structure]
** xref:new_project.adoc[Starting a new Embassy project]
** xref:best_practices.adoc[Best Practices]
-* xref:layer_by_layer.adoc[Bare metal to async]
* xref:runtime.adoc[Executor]
-* xref:delaying_a_task.adoc[Delaying a Task]
+* xref::time_keeping.adoc[Time-keeping]
+* xref:sharing_peripherals.adoc[Sharing peripherals]
* xref:hal.adoc[HAL]
+** xref:layer_by_layer.adoc[Anatomy of an async HAL]
** xref:nrf.adoc[nRF]
** xref:stm32.adoc[STM32]
* xref:bootloader.adoc[Bootloader]
diff --git a/docs/modules/ROOT/pages/basic_application.adoc b/docs/modules/ROOT/pages/basic_application.adoc
index 95792d5a0..d5aad806d 100644
--- a/docs/modules/ROOT/pages/basic_application.adoc
+++ b/docs/modules/ROOT/pages/basic_application.adoc
@@ -17,22 +17,13 @@ The first thing you’ll notice are two attributes at the top of the file. These
include::example$basic/src/main.rs[lines="1..2"]
----
-=== Rust Nightly
-
-The next declaration is a Rust Unstable feature, which means that Embassy requires Rust Nightly:
-
-[source,rust]
-----
-include::example$basic/src/main.rs[lines="3"]
-----
-
=== Dealing with errors
Then, what follows are some declarations on how to deal with panics and faults. During development, a good practice is to rely on `defmt-rtt` and `panic-probe` to print diagnostics to the terminal:
[source,rust]
----
-include::example$basic/src/main.rs[lines="10"]
+include::example$basic/src/main.rs[lines="8"]
----
=== Task declaration
@@ -41,7 +32,7 @@ After a bit of import declaration, the tasks run by the application should be de
[source,rust]
----
-include::example$basic/src/main.rs[lines="12..20"]
+include::example$basic/src/main.rs[lines="10..18"]
----
An embassy task must be declared `async`, and may NOT take generic arguments. In this case, we are handed the LED that should be blinked and the interval of the blinking.
@@ -56,7 +47,7 @@ We then initialize the HAL with a default config, which gives us a `Peripherals`
[source,rust]
----
-include::example$basic/src/main.rs[lines="22..-1"]
+include::example$basic/src/main.rs[lines="20..-1"]
----
What happens when the `blinker` task has been spawned and main returns? Well, the main entry point is actually just like any other task, except that you can only have one and it takes some specific type arguments. The magic lies within the `#[embassy_executor::main]` macro. The macro does the following:
diff --git a/docs/modules/ROOT/pages/best_practices.adoc b/docs/modules/ROOT/pages/best_practices.adoc
index 1e02f9ba9..bfcedec06 100644
--- a/docs/modules/ROOT/pages/best_practices.adoc
+++ b/docs/modules/ROOT/pages/best_practices.adoc
@@ -3,8 +3,10 @@
Over time, a couple of best practices have emerged. The following list should serve as a guideline for developers writing embedded software in _Rust_, especially in the context of the _Embassy_ framework.
== Passing Buffers by Reference
-It may be tempting to pass arrays or wrappers, like link:https://docs.rs/heapless/latest/heapless/[`heapless::Vec`], to a function or return one just like you would with a `std::Vec`. However, in most embedded applications you don't want to spend ressources on an allocator and end up placing buffers on the stack.
-This, however, can easily blow up your stack if you are not careful.
+It may be tempting to pass arrays or wrappers, like link:https://docs.rs/heapless/latest/heapless/[`heapless::Vec`],
+to a function or return one just like you would with a `std::Vec`. However, in most embedded applications you don't
+want to spend resources on an allocator and end up placing buffers on the stack. This, however, can easily blow up
+your stack if you are not careful.
Consider the following example:
[,rust]
diff --git a/docs/modules/ROOT/pages/bootloader.adoc b/docs/modules/ROOT/pages/bootloader.adoc
index b7215e52a..3b0cdb182 100644
--- a/docs/modules/ROOT/pages/bootloader.adoc
+++ b/docs/modules/ROOT/pages/bootloader.adoc
@@ -45,6 +45,8 @@ The BOOTLOADER_STATE partition must be big enough to store one word per page in
The bootloader has a platform-agnostic part, which implements the power fail safe swapping algorithm given the boundaries set by the partitions. The platform-specific part is a minimal shim that provides additional functionality such as watchdogs or supporting the nRF52 softdevice.
+NOTE: The linker scripts for the application and bootloader look similar, but the FLASH region must point to the BOOTLOADER partition for the bootloader, and the ACTIVE partition for the application.
+
=== FirmwareUpdater
The `FirmwareUpdater` is an object for conveniently flashing firmware to the DFU partition and subsequently marking it as being ready for swapping with the active partition on the next reset. Its principle methods are `write_firmware`, which is called once per the size of the flash "write block" (typically 4KiB), and `mark_updated`, which is the final call.
@@ -91,4 +93,4 @@ cp $FIRMWARE_DIR/myfirmware $FIRMWARE_DIR/myfirmware+signed
tail -n1 $SECRETS_DIR/message.txt.sig | base64 -d -i - | dd ibs=10 skip=1 >> $FIRMWARE_DIR/myfirmware+signed
----
-Remember, guard the `$SECRETS_DIR/key.sec` key as compromising it means that another party can sign your firmware.
\ No newline at end of file
+Remember, guard the `$SECRETS_DIR/key.sec` key as compromising it means that another party can sign your firmware.
diff --git a/docs/modules/ROOT/pages/delaying_a_task.adoc b/docs/modules/ROOT/pages/delaying_a_task.adoc
deleted file mode 100644
index 3171e3515..000000000
--- a/docs/modules/ROOT/pages/delaying_a_task.adoc
+++ /dev/null
@@ -1,28 +0,0 @@
-= Delaying a Task
-
-In an embedded program, delaying a task is one of the most common actions taken. In an event loop, delays will need to be inserted to ensure
-that other tasks have a chance to run before the next iteration of the loop is called, if no other I/O is performed. Embassy provides an abstraction
-to delay the current task for a specified interval of time.
-
-Timing is serviced by the `embassy::time::Timer` struct, which provides two timing methods.
-
-`Timer::at` creates a future that completes at the specified `Instant`, relative to the system boot time.
-`Timer::after` creates a future that completes after the specified `Duration`, relative to when the future was created.
-
-An example of a delay is provided as follows:
-
-[,rust]
-----
-use embassy::executor::{task, Executor};
-use embassy::time::{Duration, Timer};
-
-#[task]
-/// Task that ticks periodically
-async fn tick_periodic() -> ! {
- loop {
- rprintln!("tick!");
- // async sleep primitive, suspends the task for 500ms.
- Timer::after(Duration::from_millis(500)).await;
- }
-}
-----
\ No newline at end of file
diff --git a/docs/modules/ROOT/pages/embassy_in_the_wild.adoc b/docs/modules/ROOT/pages/embassy_in_the_wild.adoc
index a1c31bfc7..85ad7f4a2 100644
--- a/docs/modules/ROOT/pages/embassy_in_the_wild.adoc
+++ b/docs/modules/ROOT/pages/embassy_in_the_wild.adoc
@@ -7,3 +7,5 @@ Here are known examples of real-world projects which make use of Embassy. Feel f
* link:https://github.com/card-io-ecg/card-io-fw[Card/IO firmware] - firmware for an open source ECG device
** Targets the ESP32-S3 or ESP32-C6 MCU
* The link:https://github.com/lora-rs/lora-rs[lora-rs] project includes link:https://github.com/lora-rs/lora-rs/tree/main/examples/stm32l0/src/bin[various standalone examples] for NRF52840, RP2040, STM32L0 and STM32WL
+** link:https://github.com/matoushybl/air-force-one[Air force one: A simple air quality monitoring system]
+*** Targets nRF52 and uses nrf-softdevice
diff --git a/docs/modules/ROOT/pages/faq.adoc b/docs/modules/ROOT/pages/faq.adoc
index d1a012978..6b5e6d009 100644
--- a/docs/modules/ROOT/pages/faq.adoc
+++ b/docs/modules/ROOT/pages/faq.adoc
@@ -29,13 +29,12 @@ If you see an error like this:
You are likely missing some features of the `embassy-executor` crate.
-For Cortex-M targets, consider making sure that ALL of the following features are active in your `Cargo.toml` for the `embassy-executor` crate:
+For Cortex-M targets, check whether ALL of the following features are enabled in your `Cargo.toml` for the `embassy-executor` crate:
* `arch-cortex-m`
* `executor-thread`
-* `nightly`
-For Xtensa ESP32, consider using the executors and `#[main]` macro provided by your appropriate link:https://crates.io/crates/esp-hal-common[HAL crate].
+For ESP32, consider using the executors and `#[main]` macro provided by your appropriate link:https://crates.io/crates/esp-hal-common[HAL crate].
== Why is my binary so big?
@@ -44,11 +43,12 @@ The first step to managing your binary size is to set up your link:https://doc.r
[source,toml]
----
[profile.release]
-debug = false
lto = true
opt-level = "s"
incremental = false
codegen-units = 1
+# note: debug = true is okay - debuginfo isn't flashed to the device!
+debug = true
----
All of these flags are elaborated on in the Rust Book page linked above.
@@ -118,21 +118,31 @@ features = [
]
----
+If you are in the early project setup phase and not using anything from the HAL, make sure the HAL is explicitly used to prevent the linker removing it as dead code by adding this line to your source:
+
+[source,rust]
+----
+use embassy_stm32 as _;
+----
+
== Error: `Only one package in the dependency graph may specify the same links value.`
You have multiple versions of the same crate in your dependency tree. This means that some of your
embassy crates are coming from crates.io, and some from git, each of them pulling in a different set
of dependencies.
-To resolve this issue, make sure to only use a single source for all your embassy crates! To do this,
-you should patch your dependencies to use git sources using `[patch.crates.io]` and maybe `[patch.'https://github.com/embassy-rs/embassy.git']`.
+To resolve this issue, make sure to only use a single source for all your embassy crates!
+To do this, you should patch your dependencies to use git sources using `[patch.crates.io]`
+and maybe `[patch.'https://github.com/embassy-rs/embassy.git']`.
Example:
[source,toml]
----
[patch.crates-io]
-embassy-time = { git = "https://github.com/embassy-rs/embassy.git", rev = "e5fdd35" }
+embassy-time-queue-driver = { git = "https://github.com/embassy-rs/embassy.git", rev = "e5fdd35" }
+embassy-time-driver = { git = "https://github.com/embassy-rs/embassy.git", rev = "e5fdd35" }
+# embassy-time = { git = "https://github.com/embassy-rs/embassy.git", rev = "e5fdd35" }
----
Note that the git revision should match any other embassy patches or git dependencies that you are using!
@@ -152,4 +162,49 @@ Note that the git revision should match any other embassy patches or git depende
* When using `InterruptExecutor`:
** disable `executor-thread`
** make `main`` spawn everything, then enable link:https://docs.rs/cortex-m/latest/cortex_m/peripheral/struct.SCB.html#method.set_sleeponexit[SCB.SLEEPONEXIT] and `loop { cortex_m::asm::wfi() }`
- ** *Note:* If you need 2 priority levels, using 2 interrupt executors is better than 1 thread executor + 1 interrupt executor.
\ No newline at end of file
+ ** *Note:* If you need 2 priority levels, using 2 interrupt executors is better than 1 thread executor + 1 interrupt executor.
+
+== How do I set up the task arenas on stable?
+
+When you aren't using the `nightly` feature of `embassy-executor`, the executor uses a bump allocator, which may require configuration.
+
+Something like this error will occur at **compile time** if the task arena is *too large* for the target's RAM:
+
+[source,plain]
+----
+rust-lld: error: section '.bss' will not fit in region 'RAM': overflowed by _ bytes
+rust-lld: error: section '.uninit' will not fit in region 'RAM': overflowed by _ bytes
+----
+
+And this message will appear at **runtime** if the task arena is *too small* for the tasks running:
+
+[source,plain]
+----
+ERROR panicked at 'embassy-executor: task arena is full. You must increase the arena size, see the documentation for details: https://docs.embassy.dev/embassy-executor/'
+----
+
+NOTE: If all tasks are spawned at startup, this panic will occur immediately.
+
+Check out link:https://docs.embassy.dev/embassy-executor/git/cortex-m/index.html#task-arena[Task Arena Documentation] for more details.
+
+== Can I use manual ISRs alongside Embassy?
+
+Yes! This can be useful if you need to respond to an event as fast as possible, and the latency caused by the usual “ISR, wake, return from ISR, context switch to woken task” flow is too much for your application. Simply define a `#[interrupt] fn INTERRUPT_NAME() {}` handler as you would link:https://docs.rust-embedded.org/book/start/interrupts.html[in any other embedded rust project].
+
+== How can I measure resource usage (CPU, RAM, etc.)?
+
+=== For CPU Usage:
+
+There are a couple techniques that have been documented, generally you want to measure how long you are spending in the idle or low priority loop.
+
+We need to document specifically how to do this in embassy, but link:https://blog.japaric.io/cpu-monitor/[this older post] describes the general process.
+
+If you end up doing this, please update this section with more specific examples!
+
+=== For Static Memory Usage
+
+Tools like `cargo size` and `cargo nm` can tell you the size of any globals or other static usage. Specifically you will want to see the size of the `.data` and `.bss` sections, which together make up the total global/static memory usage.
+
+=== For Max Stack Usage
+
+Check out link:https://github.com/Dirbaio/cargo-call-stack/[`cargo-call-stack`] for statically calculating worst-case stack usage. There are some caveats and inaccuracies possible with this, but this is a good way to get the general idea. See link:https://github.com/dirbaio/cargo-call-stack#known-limitations[the README] for more details.
diff --git a/docs/modules/ROOT/pages/getting_started.adoc b/docs/modules/ROOT/pages/getting_started.adoc
index ab819ac2a..73cb5530d 100644
--- a/docs/modules/ROOT/pages/getting_started.adoc
+++ b/docs/modules/ROOT/pages/getting_started.adoc
@@ -3,7 +3,7 @@
So you want to try Embassy, great! To get started, there are a few tools you need to install:
* link:https://rustup.rs/[rustup] - the Rust toolchain is needed to compile Rust code.
-* link:https://crates.io/crates/probe-rs[probe-rs] - to flash the firmware on your device. If you already have other tools like `OpenOCD` setup, you can use that as well.
+* link:https://probe.rs/[probe-rs] - to flash the firmware on your device. If you already have other tools like `OpenOCD` setup, you can use that as well.
If you don't have any supported board, don't worry: you can also run embassy on your PC using the `std` examples.
@@ -82,19 +82,19 @@ If everything worked correctly, you should see a blinking LED on your board, and
└─ blinky::__embassy_main::task::{generator#0} @ src/bin/blinky.rs:27
----
-NOTE: How does the `cargo run` command know how to connect to our board and program it? In each `examples` folder, there’s a `.cargo/config.toml` file which tells cargo to use link:https://probe.rs/[probe-rs] as the runner for ARM binaries in that folder. probe-rs handles communication with the debug probe and MCU. In order for this to work, probe-rs needs to know which chip it’s programming, so you’ll have to edit this file if you want to run examples on other chips.
+NOTE: How does the `+cargo run+` command know how to connect to our board and program it? In each `examples` folder, there’s a `.cargo/config.toml` file which tells cargo to use link:https://probe.rs/[probe-rs] as the runner for ARM binaries in that folder. probe-rs handles communication with the debug probe and MCU. In order for this to work, probe-rs needs to know which chip it’s programming, so you’ll have to edit this file if you want to run examples on other chips.
=== It didn’t work!
-If you hare having issues when running `cargo run --release`, please check the following:
+If you hare having issues when running `+cargo run --release+`, please check the following:
-* You are specifying the correct `--chip on the command line``, OR
-* You have set `.cargo/config.toml`'s run line to the correct chip, AND
-* You have changed `examples/Cargo.toml`'s HAL (e.g. embassy-stm32) dependency's feature to use the correct chip (replace the existing stm32xxxx feature)
+* You are specifying the correct `+--chip+` on the command line, OR
+* You have set `+.cargo/config.toml+`’s run line to the correct chip, AND
+* You have changed `+examples/Cargo.toml+`’s HAL (e.g. embassy-stm32) dependency's feature to use the correct chip (replace the existing stm32xxxx feature)
At this point the project should run. If you do not see a blinky LED for blinky, for example, be sure to check the code is toggling your board's LED pin.
-If you are trying to run an example with `cargo run --release` and you see the following output:
+If you are trying to run an example with `+cargo run --release+` and you see the following output:
[source]
----
0.000000 INFO Hello World!
@@ -115,6 +115,22 @@ To get rid of the frame-index error add the following to your `Cargo.toml`:
debug = 2
----
+If you’re getting an extremely long error message containing something like the following:
+
+[source]
+----
+error[E0463]: can't find crate for `std`
+ |
+ = note: the `thumbv6m-none-eabi` target may not support the standard library
+ = note: `std` is required by `stable_deref_trait` because it does not declare `#![no_std]`
+----
+
+Make sure that you didn’t accidentally run `+cargo add probe-rs+` (which adds it as a dependency) instead of link:https://probe.rs/docs/getting-started/installation/[correctly installing probe-rs].
+
+If you’re using a raspberry pi pico-w, make sure you’re running `+cargo run --bin wifi_blinky --release+` rather than the regular blinky. The pico-w’s on-board LED is connected to the WiFi chip, which needs to be initialized before the LED can be blinked.
+
+If you’re using an rp2040 debug probe (e.g. the pico probe) and are having issues after running `probe-rs info`, unplug and reconnect the probe, letting it power cycle. Running `probe-rs info` is link:https://github.com/probe-rs/probe-rs/issues/1849[known to put the pico probe into an unusable state].
+
If you’re still having problems, check the link:https://embassy.dev/book/dev/faq.html[FAQ], or ask for help in the link:https://matrix.to/#/#embassy-rs:matrix.org[Embassy Chat Room].
== What's next?
@@ -124,3 +140,4 @@ Congratulations, you have your first Embassy application running! Here are some
* Read more about the xref:runtime.adoc[executor].
* Read more about the xref:hal.adoc[HAL].
* Start xref:basic_application.adoc[writing your application].
+* Learn how to xref:new_project.adoc[start a new embassy project by adapting an example].
diff --git a/docs/modules/ROOT/pages/index.adoc b/docs/modules/ROOT/pages/index.adoc
index 6fba80eda..e17adbbd7 100644
--- a/docs/modules/ROOT/pages/index.adoc
+++ b/docs/modules/ROOT/pages/index.adoc
@@ -41,7 +41,7 @@ The link:https://docs.embassy.dev/embassy-net/[embassy-net] network stack implem
The link:https://github.com/embassy-rs/nrf-softdevice[nrf-softdevice] crate provides Bluetooth Low Energy 4.x and 5.x support for nRF52 microcontrollers.
=== LoRa
-link:https://github.com/embassy-rs/lora-phy[lora-phy] and link:https://docs.embassy.dev/embassy-lora/[embassy-lora] supports LoRa networking on a wide range of LoRa radios, fully integrated with a Rust link:https://github.com/ivajloip/rust-lorawan[LoRaWAN] implementation.
+link:https://github.com/lora-rs/lora-rs[lora-rs] supports LoRa networking on a wide range of LoRa radios, fully integrated with a Rust LoRaWAN implementation. It provides four crates — lora-phy, lora-modulation, lorawan-encoding, and lorawan-device — and basic examples for various development boards. It has support for STM32WL wireless microcontrollers or Semtech SX127x transceivers, among others.
=== USB
link:https://docs.embassy.dev/embassy-usb/[embassy-usb] implements a device-side USB stack. Implementations for common classes such as USB serial (CDC ACM) and USB HID are available, and a rich builder API allows building your own.
diff --git a/docs/modules/ROOT/pages/new_project.adoc b/docs/modules/ROOT/pages/new_project.adoc
index ce139ed8d..320966bb6 100644
--- a/docs/modules/ROOT/pages/new_project.adoc
+++ b/docs/modules/ROOT/pages/new_project.adoc
@@ -1,6 +1,17 @@
= Starting a new Embassy project
-Once you’ve successfully xref:getting_started.adoc[run some example projects], the next step is to make a standalone Embassy project. The easiest way to do this is to adapt an example for a similar chip to the one you’re targeting.
+Once you’ve successfully xref:getting_started.adoc[run some example projects], the next step is to make a standalone Embassy project.
+
+There are some tools for generating Embassy projects: (WIP)
+
+==== CLI
+- link:https://github.com/adinack/cargo-embassy[cargo-embassy] (STM32 and NRF)
+
+==== cargo-generate
+- link:https://github.com/lulf/embassy-template[embassy-template] (STM32, NRF, and RP)
+- link:https://github.com/bentwire/embassy-rp2040-template[embassy-rp2040-template] (RP)
+
+But if you want to start from scratch:
As an example, let’s create a new embassy project from scratch for a STM32G474. The same instructions are applicable for any supported chip with some minor changes.
@@ -166,13 +177,13 @@ should result in a blinking LED (if there’s one attached to the pin in `src/ma
Erasing sectors ✔ [00:00:00] [#########################################################] 18.00 KiB/18.00 KiB @ 54.09 KiB/s (eta 0s )
Programming pages ✔ [00:00:00] [#########################################################] 17.00 KiB/17.00 KiB @ 35.91 KiB/s (eta 0s ) Finished in 0.817s
0.000000 TRACE BDCR configured: 00008200
-└─ embassy_stm32::rcc::bd::{impl#3}::init::{closure#4} @ /home/you/.cargo/git/checkouts/embassy-9312dcb0ed774b29/7703f47/embassy-stm32/src/fmt.rs:117
+└─ embassy_stm32::rcc::bd::{impl#3}::init::{closure#4} @ /home/you/.cargo/git/checkouts/embassy-9312dcb0ed774b29/7703f47/embassy-stm32/src/fmt.rs:117
0.000000 DEBUG rcc: Clocks { sys: Hertz(16000000), pclk1: Hertz(16000000), pclk1_tim: Hertz(16000000), pclk2: Hertz(16000000), pclk2_tim: Hertz(16000000), hclk1: Hertz(16000000), hclk2: Hertz(16000000), pll1_p: None, adc: None, adc34: None, rtc: Some(Hertz(32000)) }
-└─ embassy_stm32::rcc::set_freqs @ /home/you/.cargo/git/checkouts/embassy-9312dcb0ed774b29/7703f47/embassy-stm32/src/fmt.rs:130
+└─ embassy_stm32::rcc::set_freqs @ /home/you/.cargo/git/checkouts/embassy-9312dcb0ed774b29/7703f47/embassy-stm32/src/fmt.rs:130
0.000000 INFO Hello World!
-└─ embassy_stm32g474::____embassy_main_task::{async_fn#0} @ src/main.rs:14
+└─ embassy_stm32g474::____embassy_main_task::{async_fn#0} @ src/main.rs:14
0.000091 INFO high
-└─ embassy_stm32g474::____embassy_main_task::{async_fn#0} @ src/main.rs:19
+└─ embassy_stm32g474::____embassy_main_task::{async_fn#0} @ src/main.rs:19
0.300201 INFO low
-└─ embassy_stm32g474::____embassy_main_task::{async_fn#0} @ src/main.rs:23
-----
\ No newline at end of file
+└─ embassy_stm32g474::____embassy_main_task::{async_fn#0} @ src/main.rs:23
+----
diff --git a/docs/modules/ROOT/pages/project_structure.adoc b/docs/modules/ROOT/pages/project_structure.adoc
index 3e6008ec4..2adfcc1df 100644
--- a/docs/modules/ROOT/pages/project_structure.adoc
+++ b/docs/modules/ROOT/pages/project_structure.adoc
@@ -18,7 +18,7 @@ my-project
|- rust-toolchain.toml
----
-=== .cargo/config.toml
+== .cargo/config.toml
This directory/file describes what platform you're on, and configures link:https://github.com/probe-rs/probe-rs[probe-rs] to deploy to your device.
@@ -36,17 +36,22 @@ target = "thumbv6m-none-eabi" # <-change for your platform
DEFMT_LOG = "trace" # <- can change to info, warn, or error
----
-=== build.rs
+== build.rs
-This is the build script for your project. It links defmt (what is defmt?) and the `memory.x` file if needed. This file is pretty specific for each chipset, just copy and paste from the corresponding link:https://github.com/embassy-rs/embassy/tree/main/examples[example].
+This is the build script for your project. It links defmt (what is link:https://defmt.ferrous-systems.com[defmt]?) and the `memory.x` file if needed. This file is pretty specific for each chipset, just copy and paste from the corresponding link:https://github.com/embassy-rs/embassy/tree/main/examples[example].
-=== Cargo.toml
+== Cargo.toml
This is your manifest file, where you can configure all of the embassy components to use the features you need.
-TODO: someone should exhaustively describe every feature for every component!
+==== Features
+===== Time
+- tick-hz-x: Configures the tick rate of `embassy-time`. Higher tick rate means higher precision, and higher CPU wakes.
+- defmt-timestamp-uptime: defmt log entries will display the uptime in seconds.
-=== memory.x
+...more to come
+
+== memory.x
This file outlines the flash/ram usage of your program. It is especially useful when using link:https://github.com/embassy-rs/nrf-softdevice[nrf-softdevice] on an nRF5x.
@@ -63,7 +68,7 @@ MEMORY
}
----
-=== rust-toolchain.toml
+== rust-toolchain.toml
This file configures the rust version and configuration to use.
diff --git a/docs/modules/ROOT/pages/sharing_peripherals.adoc b/docs/modules/ROOT/pages/sharing_peripherals.adoc
new file mode 100644
index 000000000..fcba0e27b
--- /dev/null
+++ b/docs/modules/ROOT/pages/sharing_peripherals.adoc
@@ -0,0 +1,126 @@
+= Sharing peripherals between tasks
+
+Often times, more than one task needs access to the same resource (pin, communication interface, etc.). Embassy provides many different synchronization primitives in the link:https://crates.io/crates/embassy-sync[embassy-sync] crate.
+
+The following examples shows different ways to use the on-board LED on a Raspberry Pi Pico board by two tasks simultaneously.
+
+== Sharing using a Mutex
+
+Using mutual exclusion is the simplest way to share a peripheral.
+
+[,rust]
+----
+use defmt::*;
+use embassy_executor::Spawner;
+use embassy_rp::gpio;
+use embassy_sync::blocking_mutex::raw::ThreadModeRawMutex;
+use embassy_sync::mutex::Mutex;
+use embassy_time::{Duration, Ticker};
+use gpio::{AnyPin, Level, Output};
+use {defmt_rtt as _, panic_probe as _};
+
+type LedType = Mutex>>;
+static LED: LedType = Mutex::new(None);
+
+#[embassy_executor::main]
+async fn main(spawner: Spawner) {
+ let p = embassy_rp::init(Default::default());
+ // set the content of the global LED reference to the real LED pin
+ let led = Output::new(AnyPin::from(p.PIN_25), Level::High);
+ // inner scope is so that once the mutex is written to, the MutexGuard is dropped, thus the
+ // Mutex is released
+ {
+ *(LED.lock().await) = Some(led);
+ }
+ let dt = 100 * 1_000_000;
+ let k = 1.003;
+
+ unwrap!(spawner.spawn(toggle_led(&LED, Duration::from_nanos(dt))));
+ unwrap!(spawner.spawn(toggle_led(&LED, Duration::from_nanos((dt as f64 * k) as u64))));
+}
+
+// A pool size of 2 means you can spawn two instances of this task.
+#[embassy_executor::task(pool_size = 2)]
+async fn toggle_led(led: &'static LedType, delay: Duration) {
+ let mut ticker = Ticker::every(delay);
+ loop {
+ {
+ let mut led_unlocked = led.lock().await;
+ if let Some(pin_ref) = led_unlocked.as_mut() {
+ pin_ref.toggle();
+ }
+ }
+ ticker.next().await;
+ }
+}
+----
+
+The structure facilitating access to the resource is the defined `LedType`.
+
+=== Why so complicated
+
+Unwrapping the layers gives insight into why each one is needed.
+
+==== `Mutex`
+
+The mutex is there so if one task gets the resource first and begins modifying it, all other tasks wanting to write will have to wait (the `led.lock().await` will return immediately if no task has locked the mutex, and will block if it is accessed somewhere else).
+
+==== `Option`
+
+The `LED` variable needs to be defined outside the main task as references accepted by tasks need to be `'static`. However, if it is outside the main task, it cannot be initialised to point to any pin, as the pins themselves are not initialised. Thus, it is set to `None`.
+
+==== `Output`
+
+To indicate that the pin will be set to an Output. The `AnyPin` could have been `embassy_rp::peripherals::PIN_25`, however this option lets the `toggle_led` function be more generic.
+
+== Sharing using a Channel
+
+A channel is another way to ensure exclusive access to a resource. Using a channel is great in the cases where the access can happen at a later point in time, allowing you to enqueue operations and do other things.
+
+[,rust]
+----
+use defmt::*;
+use embassy_executor::Spawner;
+use embassy_rp::gpio;
+use embassy_sync::blocking_mutex::raw::ThreadModeRawMutex;
+use embassy_sync::channel::{Channel, Sender};
+use embassy_time::{Duration, Ticker};
+use gpio::{AnyPin, Level, Output};
+use {defmt_rtt as _, panic_probe as _};
+
+enum LedState {
+ Toggle,
+}
+static CHANNEL: Channel = Channel::new();
+
+#[embassy_executor::main]
+async fn main(spawner: Spawner) {
+ let p = embassy_rp::init(Default::default());
+ let mut led = Output::new(AnyPin::from(p.PIN_25), Level::High);
+
+ let dt = 100 * 1_000_000;
+ let k = 1.003;
+
+ unwrap!(spawner.spawn(toggle_led(CHANNEL.sender(), Duration::from_nanos(dt))));
+ unwrap!(spawner.spawn(toggle_led(CHANNEL.sender(), Duration::from_nanos((dt as f64 * k) as u64))));
+
+ loop {
+ match CHANNEL.receive().await {
+ LedState::Toggle => led.toggle(),
+ }
+ }
+}
+
+// A pool size of 2 means you can spawn two instances of this task.
+#[embassy_executor::task(pool_size = 2)]
+async fn toggle_led(control: Sender<'static, ThreadModeRawMutex, LedState, 64>, delay: Duration) {
+ let mut ticker = Ticker::every(delay);
+ loop {
+ control.send(LedState::Toggle).await;
+ ticker.next().await;
+ }
+}
+----
+
+This example replaces the Mutex with a Channel, and uses another task (the main loop) to drive the LED. The advantage of this approach is that only a single task references the peripheral, separating concerns. However, using a Mutex has a lower overhead and might be necessary if you need to ensure
+that the operation is ecompleted before continuing to do other work in your task.
diff --git a/docs/modules/ROOT/pages/time_keeping.adoc b/docs/modules/ROOT/pages/time_keeping.adoc
new file mode 100644
index 000000000..5068216ed
--- /dev/null
+++ b/docs/modules/ROOT/pages/time_keeping.adoc
@@ -0,0 +1,60 @@
+= Time-keeping
+
+In an embedded program, delaying a task is one of the most common actions taken. In an event loop, delays will need to be inserted to ensure
+that other tasks have a chance to run before the next iteration of the loop is called, if no other I/O is performed. Embassy provides abstractions
+to delay the current task for a specified interval of time.
+
+The interface for time-keeping in Embassy is handled by the link:https://crates.io/crates/embassy-time[embassy-time] crate. The types can be used with the internal
+timer queue in link:https://crates.io/crates/embassy-executor[embassy-executor] or a custom timer queue implementation.
+
+== Timer
+
+The `embassy::time::Timer` type provides two timing methods.
+
+`Timer::at` creates a future that completes at the specified `Instant`, relative to the system boot time.
+`Timer::after` creates a future that completes after the specified `Duration`, relative to when the future was created.
+
+An example of a delay is provided as follows:
+
+[,rust]
+----
+use embassy::executor::{task, Executor};
+use embassy::time::{Duration, Timer};
+
+#[task]
+/// Task that ticks periodically
+async fn tick_periodic() -> ! {
+ loop {
+ rprintln!("tick!");
+ // async sleep primitive, suspends the task for 500ms.
+ Timer::after(Duration::from_millis(500)).await;
+ }
+}
+----
+
+== Delay
+
+The `embassy::time::Delay` type provides an implementation of the link:https://docs.rs/embedded-hal/1.0.0/embedded_hal/delay/index.html[embedded-hal] and
+link:https://docs.rs/embedded-hal-async/latest/embedded_hal_async/delay/index.html[embedded-hal-async] traits. This can be used for drivers
+that expect a generic delay implementation to be provided.
+
+An example of how this can be used:
+
+[,rust]
+----
+use embassy::executor::{task, Executor};
+
+#[task]
+/// Task that ticks periodically
+async fn tick_periodic() -> ! {
+ loop {
+ rprintln!("tick!");
+ // async sleep primitive, suspends the task for 500ms.
+ generic_delay(embassy::time::Delay).await
+ }
+}
+
+async fn generic_delay(delay: D) {
+ delay.delay_ms(500).await;
+}
+----
diff --git a/embassy-boot/nrf/Cargo.toml b/embassy-boot-nrf/Cargo.toml
similarity index 57%
rename from embassy-boot/nrf/Cargo.toml
rename to embassy-boot-nrf/Cargo.toml
index eea29cf2e..c056dc66a 100644
--- a/embassy-boot/nrf/Cargo.toml
+++ b/embassy-boot-nrf/Cargo.toml
@@ -1,13 +1,20 @@
[package]
edition = "2021"
name = "embassy-boot-nrf"
-version = "0.1.0"
+version = "0.2.0"
description = "Bootloader lib for nRF chips"
license = "MIT OR Apache-2.0"
+repository = "https://github.com/embassy-rs/embassy"
+documentation = "https://docs.embassy.dev/embassy-boot-nrf"
+categories = [
+ "embedded",
+ "no-std",
+ "asynchronous",
+]
[package.metadata.embassy_docs]
-src_base = "https://github.com/embassy-rs/embassy/blob/embassy-boot-nrf-v$VERSION/embassy-boot/nrf/src/"
-src_base_git = "https://github.com/embassy-rs/embassy/blob/$COMMIT/embassy-boot/nrf/src/"
+src_base = "https://github.com/embassy-rs/embassy/blob/embassy-boot-nrf-v$VERSION/embassy-boot-nrf/src/"
+src_base_git = "https://github.com/embassy-rs/embassy/blob/$COMMIT/embassy-boot-nrf/src/"
features = ["embassy-nrf/nrf52840"]
target = "thumbv7em-none-eabi"
@@ -16,16 +23,16 @@ target = "thumbv7em-none-eabi"
[dependencies]
defmt = { version = "0.3", optional = true }
-embassy-sync = { version = "0.5.0", path = "../../embassy-sync" }
-embassy-nrf = { path = "../../embassy-nrf" }
-embassy-boot = { path = "../boot", default-features = false }
+embassy-sync = { version = "0.5.0", path = "../embassy-sync" }
+embassy-nrf = { version = "0.1.0", path = "../embassy-nrf", default-features = false }
+embassy-boot = { version = "0.2.0", path = "../embassy-boot" }
cortex-m = { version = "0.7.6" }
cortex-m-rt = { version = "0.7" }
embedded-storage = "0.3.1"
embedded-storage-async = { version = "0.4.1" }
cfg-if = "1.0.0"
-nrf-softdevice-mbr = { version = "0.1.0", git = "https://github.com/embassy-rs/nrf-softdevice.git", branch = "master", optional = true }
+nrf-softdevice-mbr = { version = "0.2.0", optional = true }
[features]
defmt = [
diff --git a/embassy-boot-nrf/README.md b/embassy-boot-nrf/README.md
new file mode 100644
index 000000000..9dc5b0eb9
--- /dev/null
+++ b/embassy-boot-nrf/README.md
@@ -0,0 +1,11 @@
+# embassy-boot-nrf
+
+An [Embassy](https://embassy.dev) project.
+
+An adaptation of `embassy-boot` for nRF.
+
+## Features
+
+* Load applications with or without the softdevice.
+* Configure bootloader partitions based on linker script.
+* Using watchdog timer to detect application failure.
diff --git a/embassy-boot/stm32/src/fmt.rs b/embassy-boot-nrf/src/fmt.rs
similarity index 99%
rename from embassy-boot/stm32/src/fmt.rs
rename to embassy-boot-nrf/src/fmt.rs
index 78e583c1c..2ac42c557 100644
--- a/embassy-boot/stm32/src/fmt.rs
+++ b/embassy-boot-nrf/src/fmt.rs
@@ -1,5 +1,5 @@
#![macro_use]
-#![allow(unused_macros)]
+#![allow(unused)]
use core::fmt::{Debug, Display, LowerHex};
@@ -229,7 +229,6 @@ impl Try for Result {
}
}
-#[allow(unused)]
pub(crate) struct Bytes<'a>(pub &'a [u8]);
impl<'a> Debug for Bytes<'a> {
diff --git a/embassy-boot/nrf/src/lib.rs b/embassy-boot-nrf/src/lib.rs
similarity index 89%
rename from embassy-boot/nrf/src/lib.rs
rename to embassy-boot-nrf/src/lib.rs
index 5b20a93c6..d53e78895 100644
--- a/embassy-boot/nrf/src/lib.rs
+++ b/embassy-boot-nrf/src/lib.rs
@@ -4,8 +4,8 @@
mod fmt;
pub use embassy_boot::{
- AlignedBuffer, BlockingFirmwareState, BlockingFirmwareUpdater, BootLoaderConfig, FirmwareState, FirmwareUpdater,
- FirmwareUpdaterConfig,
+ AlignedBuffer, BlockingFirmwareState, BlockingFirmwareUpdater, BootError, BootLoaderConfig, FirmwareState,
+ FirmwareUpdater, FirmwareUpdaterConfig,
};
use embassy_nrf::nvmc::PAGE_SIZE;
use embassy_nrf::peripherals::WDT;
@@ -16,14 +16,21 @@ use embedded_storage::nor_flash::{ErrorType, NorFlash, ReadNorFlash};
pub struct BootLoader;
impl BootLoader {
- /// Inspect the bootloader state and perform actions required before booting, such as swapping firmware.
+ /// Inspect the bootloader state and perform actions required before booting, such as swapping firmware
pub fn prepare(
config: BootLoaderConfig,
) -> Self {
+ Self::try_prepare::(config).expect("Boot prepare error")
+ }
+
+ /// Inspect the bootloader state and perform actions required before booting, such as swapping firmware
+ pub fn try_prepare(
+ config: BootLoaderConfig,
+ ) -> Result {
let mut aligned_buf = AlignedBuffer([0; BUFFER_SIZE]);
let mut boot = embassy_boot::BootLoader::new(config);
- boot.prepare_boot(&mut aligned_buf.0).expect("Boot prepare error");
- Self
+ let _state = boot.prepare_boot(aligned_buf.as_mut())?;
+ Ok(Self)
}
/// Boots the application without softdevice mechanisms.
diff --git a/embassy-boot/rp/Cargo.toml b/embassy-boot-rp/Cargo.toml
similarity index 74%
rename from embassy-boot/rp/Cargo.toml
rename to embassy-boot-rp/Cargo.toml
index 0f2dc4628..305bc5995 100644
--- a/embassy-boot/rp/Cargo.toml
+++ b/embassy-boot-rp/Cargo.toml
@@ -1,13 +1,20 @@
[package]
edition = "2021"
name = "embassy-boot-rp"
-version = "0.1.0"
+version = "0.2.0"
description = "Bootloader lib for RP2040 chips"
license = "MIT OR Apache-2.0"
+repository = "https://github.com/embassy-rs/embassy"
+documentation = "https://docs.embassy.dev/embassy-boot-rp"
+categories = [
+ "embedded",
+ "no-std",
+ "asynchronous",
+]
[package.metadata.embassy_docs]
src_base = "https://github.com/embassy-rs/embassy/blob/embassy-boot-rp-v$VERSION/src/"
-src_base_git = "https://github.com/embassy-rs/embassy/blob/$COMMIT/embassy-boot/rp/src/"
+src_base_git = "https://github.com/embassy-rs/embassy/blob/$COMMIT/embassy-boot-rp/src/"
target = "thumbv6m-none-eabi"
[lib]
@@ -17,10 +24,10 @@ defmt = { version = "0.3", optional = true }
defmt-rtt = { version = "0.4", optional = true }
log = { version = "0.4", optional = true }
-embassy-sync = { version = "0.5.0", path = "../../embassy-sync" }
-embassy-rp = { path = "../../embassy-rp", default-features = false }
-embassy-boot = { path = "../boot", default-features = false }
-embassy-time = { path = "../../embassy-time" }
+embassy-sync = { version = "0.5.0", path = "../embassy-sync" }
+embassy-rp = { version = "0.1.0", path = "../embassy-rp", default-features = false }
+embassy-boot = { version = "0.2.0", path = "../embassy-boot" }
+embassy-time = { version = "0.3.0", path = "../embassy-time" }
cortex-m = { version = "0.7.6" }
cortex-m-rt = { version = "0.7" }
diff --git a/embassy-boot-rp/README.md b/embassy-boot-rp/README.md
new file mode 100644
index 000000000..b664145a9
--- /dev/null
+++ b/embassy-boot-rp/README.md
@@ -0,0 +1,12 @@
+# embassy-boot-rp
+
+An [Embassy](https://embassy.dev) project.
+
+An adaptation of `embassy-boot` for RP2040.
+
+NOTE: The applications using this bootloader should not link with the `link-rp.x` linker script.
+
+## Features
+
+* Configure bootloader partitions based on linker script.
+* Load applications from active partition.
diff --git a/embassy-boot/rp/build.rs b/embassy-boot-rp/build.rs
similarity index 100%
rename from embassy-boot/rp/build.rs
rename to embassy-boot-rp/build.rs
diff --git a/embassy-boot/nrf/src/fmt.rs b/embassy-boot-rp/src/fmt.rs
similarity index 99%
rename from embassy-boot/nrf/src/fmt.rs
rename to embassy-boot-rp/src/fmt.rs
index 78e583c1c..2ac42c557 100644
--- a/embassy-boot/nrf/src/fmt.rs
+++ b/embassy-boot-rp/src/fmt.rs
@@ -1,5 +1,5 @@
#![macro_use]
-#![allow(unused_macros)]
+#![allow(unused)]
use core::fmt::{Debug, Display, LowerHex};
@@ -229,7 +229,6 @@ impl Try for Result {
}
}
-#[allow(unused)]
pub(crate) struct Bytes<'a>(pub &'a [u8]);
impl<'a> Debug for Bytes<'a> {
diff --git a/embassy-boot/rp/src/lib.rs b/embassy-boot-rp/src/lib.rs
similarity index 85%
rename from embassy-boot/rp/src/lib.rs
rename to embassy-boot-rp/src/lib.rs
index 07a5b3f4d..d0a393bed 100644
--- a/embassy-boot/rp/src/lib.rs
+++ b/embassy-boot-rp/src/lib.rs
@@ -4,8 +4,8 @@
mod fmt;
pub use embassy_boot::{
- AlignedBuffer, BlockingFirmwareState, BlockingFirmwareUpdater, BootLoaderConfig, FirmwareState, FirmwareUpdater,
- FirmwareUpdaterConfig, State,
+ AlignedBuffer, BlockingFirmwareState, BlockingFirmwareUpdater, BootError, BootLoaderConfig, FirmwareState,
+ FirmwareUpdater, FirmwareUpdaterConfig, State,
};
use embassy_rp::flash::{Blocking, Flash, ERASE_SIZE};
use embassy_rp::peripherals::{FLASH, WATCHDOG};
@@ -21,10 +21,17 @@ impl BootLoader {
pub fn prepare(
config: BootLoaderConfig,
) -> Self {
+ Self::try_prepare::(config).expect("Boot prepare error")
+ }
+
+ /// Inspect the bootloader state and perform actions required before booting, such as swapping firmware
+ pub fn try_prepare(
+ config: BootLoaderConfig,
+ ) -> Result {
let mut aligned_buf = AlignedBuffer([0; BUFFER_SIZE]);
let mut boot = embassy_boot::BootLoader::new(config);
- boot.prepare_boot(aligned_buf.as_mut()).expect("Boot prepare error");
- Self
+ let _state = boot.prepare_boot(aligned_buf.as_mut())?;
+ Ok(Self)
}
/// Boots the application.
diff --git a/embassy-boot/stm32/Cargo.toml b/embassy-boot-stm32/Cargo.toml
similarity index 74%
rename from embassy-boot/stm32/Cargo.toml
rename to embassy-boot-stm32/Cargo.toml
index bc8da6738..6f8fbe355 100644
--- a/embassy-boot/stm32/Cargo.toml
+++ b/embassy-boot-stm32/Cargo.toml
@@ -1,13 +1,20 @@
[package]
edition = "2021"
name = "embassy-boot-stm32"
-version = "0.1.0"
+version = "0.2.0"
description = "Bootloader lib for STM32 chips"
license = "MIT OR Apache-2.0"
+repository = "https://github.com/embassy-rs/embassy"
+documentation = "https://docs.embassy.dev/embassy-boot-stm32"
+categories = [
+ "embedded",
+ "no-std",
+ "asynchronous",
+]
[package.metadata.embassy_docs]
-src_base = "https://github.com/embassy-rs/embassy/blob/embassy-boot-nrf-v$VERSION/embassy-boot/stm32/src/"
-src_base_git = "https://github.com/embassy-rs/embassy/blob/$COMMIT/embassy-boot/stm32/src/"
+src_base = "https://github.com/embassy-rs/embassy/blob/embassy-boot-nrf-v$VERSION/embassy-boot-stm32/src/"
+src_base_git = "https://github.com/embassy-rs/embassy/blob/$COMMIT/embassy-boot-stm32/src/"
features = ["embassy-stm32/stm32f429zi"]
target = "thumbv7em-none-eabi"
@@ -18,9 +25,9 @@ defmt = { version = "0.3", optional = true }
defmt-rtt = { version = "0.4", optional = true }
log = { version = "0.4", optional = true }
-embassy-sync = { version = "0.5.0", path = "../../embassy-sync" }
-embassy-stm32 = { path = "../../embassy-stm32", default-features = false }
-embassy-boot = { path = "../boot", default-features = false }
+embassy-sync = { version = "0.5.0", path = "../embassy-sync" }
+embassy-stm32 = { version = "0.1.0", path = "../embassy-stm32", default-features = false }
+embassy-boot = { version = "0.2.0", path = "../embassy-boot" }
cortex-m = { version = "0.7.6" }
cortex-m-rt = { version = "0.7" }
embedded-storage = "0.3.1"
diff --git a/embassy-boot-stm32/README.md b/embassy-boot-stm32/README.md
new file mode 100644
index 000000000..f6dadc8e7
--- /dev/null
+++ b/embassy-boot-stm32/README.md
@@ -0,0 +1,10 @@
+# embassy-boot-stm32
+
+An [Embassy](https://embassy.dev) project.
+
+An adaptation of `embassy-boot` for STM32.
+
+## Features
+
+* Configure bootloader partitions based on linker script.
+* Load applications from active partition.
diff --git a/embassy-boot/stm32/build.rs b/embassy-boot-stm32/build.rs
similarity index 100%
rename from embassy-boot/stm32/build.rs
rename to embassy-boot-stm32/build.rs
diff --git a/embassy-boot/rp/src/fmt.rs b/embassy-boot-stm32/src/fmt.rs
similarity index 99%
rename from embassy-boot/rp/src/fmt.rs
rename to embassy-boot-stm32/src/fmt.rs
index 78e583c1c..2ac42c557 100644
--- a/embassy-boot/rp/src/fmt.rs
+++ b/embassy-boot-stm32/src/fmt.rs
@@ -1,5 +1,5 @@
#![macro_use]
-#![allow(unused_macros)]
+#![allow(unused)]
use core::fmt::{Debug, Display, LowerHex};
@@ -229,7 +229,6 @@ impl Try for Result {
}
}
-#[allow(unused)]
pub(crate) struct Bytes<'a>(pub &'a [u8]);
impl<'a> Debug for Bytes<'a> {
diff --git a/embassy-boot/stm32/src/lib.rs b/embassy-boot-stm32/src/lib.rs
similarity index 62%
rename from embassy-boot/stm32/src/lib.rs
rename to embassy-boot-stm32/src/lib.rs
index c418cb262..708441835 100644
--- a/embassy-boot/stm32/src/lib.rs
+++ b/embassy-boot-stm32/src/lib.rs
@@ -4,23 +4,33 @@
mod fmt;
pub use embassy_boot::{
- AlignedBuffer, BlockingFirmwareState, BlockingFirmwareUpdater, BootLoaderConfig, FirmwareState, FirmwareUpdater,
- FirmwareUpdaterConfig, State,
+ AlignedBuffer, BlockingFirmwareState, BlockingFirmwareUpdater, BootError, BootLoaderConfig, FirmwareState,
+ FirmwareUpdater, FirmwareUpdaterConfig, State,
};
use embedded_storage::nor_flash::NorFlash;
/// A bootloader for STM32 devices.
-pub struct BootLoader;
+pub struct BootLoader {
+ /// The reported state of the bootloader after preparing for boot
+ pub state: State,
+}
impl BootLoader {
/// Inspect the bootloader state and perform actions required before booting, such as swapping firmware
pub fn prepare(
config: BootLoaderConfig,
) -> Self {
+ Self::try_prepare::(config).expect("Boot prepare error")
+ }
+
+ /// Inspect the bootloader state and perform actions required before booting, such as swapping firmware
+ pub fn try_prepare(
+ config: BootLoaderConfig,
+ ) -> Result {
let mut aligned_buf = AlignedBuffer([0; BUFFER_SIZE]);
let mut boot = embassy_boot::BootLoader::new(config);
- boot.prepare_boot(aligned_buf.as_mut()).expect("Boot prepare error");
- Self
+ let state = boot.prepare_boot(aligned_buf.as_mut())?;
+ Ok(Self { state })
}
/// Boots the application.
diff --git a/embassy-boot/boot/Cargo.toml b/embassy-boot/Cargo.toml
similarity index 61%
rename from embassy-boot/boot/Cargo.toml
rename to embassy-boot/Cargo.toml
index dd2ff8158..242caa229 100644
--- a/embassy-boot/boot/Cargo.toml
+++ b/embassy-boot/Cargo.toml
@@ -1,10 +1,11 @@
[package]
edition = "2021"
name = "embassy-boot"
-version = "0.1.1"
+version = "0.2.0"
description = "A lightweight bootloader supporting firmware updates in a power-fail-safe way, with trial boots and rollbacks."
license = "MIT OR Apache-2.0"
repository = "https://github.com/embassy-rs/embassy"
+documentation = "https://docs.embassy.dev/embassy-boot"
categories = [
"embedded",
"no-std",
@@ -12,8 +13,8 @@ categories = [
]
[package.metadata.embassy_docs]
-src_base = "https://github.com/embassy-rs/embassy/blob/embassy-boot-v$VERSION/embassy-boot/boot/src/"
-src_base_git = "https://github.com/embassy-rs/embassy/blob/$COMMIT/embassy-boot/boot/src/"
+src_base = "https://github.com/embassy-rs/embassy/blob/embassy-boot-v$VERSION/embassy-boot/src/"
+src_base_git = "https://github.com/embassy-rs/embassy/blob/$COMMIT/embassy-boot/src/"
target = "thumbv7em-none-eabi"
features = ["defmt"]
@@ -26,25 +27,22 @@ features = ["defmt"]
defmt = { version = "0.3", optional = true }
digest = "0.10"
log = { version = "0.4", optional = true }
-ed25519-dalek = { version = "1.0.1", default_features = false, features = ["u32_backend"], optional = true }
-embassy-embedded-hal = { version = "0.1.0", path = "../../embassy-embedded-hal" }
-embassy-sync = { version = "0.5.0", path = "../../embassy-sync" }
+ed25519-dalek = { version = "2", default_features = false, features = ["digest"], optional = true }
+embassy-embedded-hal = { version = "0.1.0", path = "../embassy-embedded-hal" }
+embassy-sync = { version = "0.5.0", path = "../embassy-sync" }
embedded-storage = "0.3.1"
embedded-storage-async = { version = "0.4.1" }
-salty = { git = "https://github.com/ycrypto/salty.git", rev = "a9f17911a5024698406b75c0fac56ab5ccf6a8c7", optional = true }
-signature = { version = "1.6.4", default-features = false }
+salty = { version = "0.3", optional = true }
+signature = { version = "2.0", default-features = false }
[dev-dependencies]
log = "0.4"
env_logger = "0.9"
-rand = "0.7" # ed25519-dalek v1.0.1 depends on this exact version
+rand = "0.8"
futures = { version = "0.3", features = ["executor"] }
sha1 = "0.10.5"
critical-section = { version = "1.1.1", features = ["std"] }
-
-[dev-dependencies.ed25519-dalek]
-default_features = false
-features = ["rand", "std", "u32_backend"]
+ed25519-dalek = { version = "2", default_features = false, features = ["std", "rand_core", "digest"] }
[features]
ed25519-dalek = ["dep:ed25519-dalek", "_verify"]
diff --git a/embassy-boot/README.md b/embassy-boot/README.md
new file mode 100644
index 000000000..3c2d45e96
--- /dev/null
+++ b/embassy-boot/README.md
@@ -0,0 +1,35 @@
+# embassy-boot
+
+An [Embassy](https://embassy.dev) project.
+
+A lightweight bootloader supporting firmware updates in a power-fail-safe way, with trial boots and rollbacks.
+
+The bootloader can be used either as a library or be flashed directly with the default configuration derived from linker scripts.
+
+By design, the bootloader does not provide any network capabilities. Networking capabilities for fetching new firmware can be provided by the user application, using the bootloader as a library for updating the firmware, or by using the bootloader as a library and adding this capability yourself.
+
+## Overview
+
+The bootloader divides the storage into 4 main partitions, configurable when creating the bootloader instance or via linker scripts:
+
+* BOOTLOADER - Where the bootloader is placed. The bootloader itself consumes about 8kB of flash, but if you need to debug it and have space available, increasing this to 24kB will allow you to run the bootloader with probe-rs.
+* ACTIVE - Where the main application is placed. The bootloader will attempt to load the application at the start of this partition. The minimum size required for this partition is the size of your application.
+* DFU - Where the application-to-be-swapped is placed. This partition is written to by the application. This partition must be at least 1 page bigger than the ACTIVE partition.
+* BOOTLOADER STATE - Where the bootloader stores the current state describing if the active and dfu partitions need to be swapped.
+
+For any partition, the following preconditions are required:
+
+* Partitions must be aligned on the page size.
+* Partitions must be a multiple of the page size.
+
+The linker scripts for the application and bootloader look similar, but the FLASH region must point to the BOOTLOADER partition for the bootloader, and the ACTIVE partition for the application.
+
+For more details on the bootloader, see [the documentation](https://embassy.dev/book/dev/bootloader.html).
+
+## Hardware support
+
+The bootloader supports different hardware in separate crates:
+
+* `embassy-boot-nrf` - for the nRF microcontrollers.
+* `embassy-boot-rp` - for the RP2040 microcontrollers.
+* `embassy-boot-stm32` - for the STM32 microcontrollers.
diff --git a/embassy-boot/boot/README.md b/embassy-boot/boot/README.md
deleted file mode 100644
index 07755bc6c..000000000
--- a/embassy-boot/boot/README.md
+++ /dev/null
@@ -1,31 +0,0 @@
-# embassy-boot
-
-An [Embassy](https://embassy.dev) project.
-
-A lightweight bootloader supporting firmware updates in a power-fail-safe way, with trial boots and rollbacks.
-
-The bootloader can be used either as a library or be flashed directly with the default configuration derived from linker scripts.
-
-By design, the bootloader does not provide any network capabilities. Networking capabilities for fetching new firmware can be provided by the user application, using the bootloader as a library for updating the firmware, or by using the bootloader as a library and adding this capability yourself.
-
-## Hardware support
-
-The bootloader supports different hardware in separate crates:
-
-* `embassy-boot-nrf` - for the nRF microcontrollers.
-* `embassy-boot-rp` - for the RP2040 microcontrollers.
-* `embassy-boot-stm32` - for the STM32 microcontrollers.
-
-## Minimum supported Rust version (MSRV)
-
-`embassy-boot` is guaranteed to compile on the latest stable Rust version at the time of release. It might compile with older versions but that may change in any new patch release.
-
-## License
-
-This work is licensed under either of
-
-- Apache License, Version 2.0 ([LICENSE-APACHE](LICENSE-APACHE) or
- )
-- MIT license ([LICENSE-MIT](LICENSE-MIT) or )
-
-at your option.
diff --git a/embassy-boot/nrf/README.md b/embassy-boot/nrf/README.md
deleted file mode 100644
index fe581823d..000000000
--- a/embassy-boot/nrf/README.md
+++ /dev/null
@@ -1,26 +0,0 @@
-# embassy-boot-nrf
-
-An [Embassy](https://embassy.dev) project.
-
-An adaptation of `embassy-boot` for nRF.
-
-## Features
-
-* Load applications with or without the softdevice.
-* Configure bootloader partitions based on linker script.
-* Using watchdog timer to detect application failure.
-
-
-## Minimum supported Rust version (MSRV)
-
-`embassy-boot-nrf` is guaranteed to compile on the latest stable Rust version at the time of release. It might compile with older versions but that may change in any new patch release.
-
-## License
-
-This work is licensed under either of
-
-- Apache License, Version 2.0 ([LICENSE-APACHE](LICENSE-APACHE) or
- )
-- MIT license ([LICENSE-MIT](LICENSE-MIT) or )
-
-at your option.
diff --git a/embassy-boot/rp/README.md b/embassy-boot/rp/README.md
deleted file mode 100644
index 315d655e3..000000000
--- a/embassy-boot/rp/README.md
+++ /dev/null
@@ -1,26 +0,0 @@
-# embassy-boot-rp
-
-An [Embassy](https://embassy.dev) project.
-
-An adaptation of `embassy-boot` for RP2040.
-
-NOTE: The applications using this bootloader should not link with the `link-rp.x` linker script.
-
-## Features
-
-* Configure bootloader partitions based on linker script.
-* Load applications from active partition.
-
-## Minimum supported Rust version (MSRV)
-
-`embassy-boot-rp` is guaranteed to compile on the latest stable Rust version at the time of release. It might compile with older versions but that may change in any new patch release.
-
-## License
-
-This work is licensed under either of
-
-- Apache License, Version 2.0 ([LICENSE-APACHE](LICENSE-APACHE) or
- )
-- MIT license ([LICENSE-MIT](LICENSE-MIT) or )
-
-at your option.
diff --git a/embassy-boot/boot/src/boot_loader.rs b/embassy-boot/src/boot_loader.rs
similarity index 77%
rename from embassy-boot/boot/src/boot_loader.rs
rename to embassy-boot/src/boot_loader.rs
index a8c19197b..a38558056 100644
--- a/embassy-boot/boot/src/boot_loader.rs
+++ b/embassy-boot/src/boot_loader.rs
@@ -5,7 +5,7 @@ use embassy_sync::blocking_mutex::raw::NoopRawMutex;
use embassy_sync::blocking_mutex::Mutex;
use embedded_storage::nor_flash::{NorFlash, NorFlashError, NorFlashErrorKind};
-use crate::{State, BOOT_MAGIC, STATE_ERASE_VALUE, SWAP_MAGIC};
+use crate::{State, BOOT_MAGIC, DFU_DETACH_MAGIC, STATE_ERASE_VALUE, SWAP_MAGIC};
/// Errors returned by bootloader
#[derive(PartialEq, Eq, Debug)]
@@ -49,16 +49,51 @@ pub struct BootLoaderConfig {
pub state: STATE,
}
-impl<'a, FLASH: NorFlash>
+impl<'a, ACTIVE: NorFlash, DFU: NorFlash, STATE: NorFlash>
BootLoaderConfig<
- BlockingPartition<'a, NoopRawMutex, FLASH>,
- BlockingPartition<'a, NoopRawMutex, FLASH>,
- BlockingPartition<'a, NoopRawMutex, FLASH>,
+ BlockingPartition<'a, NoopRawMutex, ACTIVE>,
+ BlockingPartition<'a, NoopRawMutex, DFU>,
+ BlockingPartition<'a, NoopRawMutex, STATE>,
>
{
- /// Create a bootloader config from the flash and address symbols defined in the linkerfile
+ /// Constructs a `BootLoaderConfig` instance from flash memory and address symbols defined in the linker file.
+ ///
+ /// This method initializes `BlockingPartition` instances for the active, DFU (Device Firmware Update),
+ /// and state partitions, leveraging start and end addresses specified by the linker. These partitions
+ /// are critical for managing firmware updates, application state, and boot operations within the bootloader.
+ ///
+ /// # Parameters
+ /// - `active_flash`: A reference to a mutex-protected `RefCell` for the active partition's flash interface.
+ /// - `dfu_flash`: A reference to a mutex-protected `RefCell` for the DFU partition's flash interface.
+ /// - `state_flash`: A reference to a mutex-protected `RefCell` for the state partition's flash interface.
+ ///
+ /// # Safety
+ /// The method contains `unsafe` blocks for dereferencing raw pointers that represent the start and end addresses
+ /// of the bootloader's partitions in flash memory. It is crucial that these addresses are accurately defined
+ /// in the memory.x file to prevent undefined behavior.
+ ///
+ /// The caller must ensure that the memory regions defined by these symbols are valid and that the flash memory
+ /// interfaces provided are compatible with these regions.
+ ///
+ /// # Returns
+ /// A `BootLoaderConfig` instance with `BlockingPartition` instances for the active, DFU, and state partitions.
+ ///
+ /// # Example
+ /// ```ignore
+ /// // Assume `active_flash`, `dfu_flash`, and `state_flash` all share the same flash memory interface.
+ /// let layout = Flash::new_blocking(p.FLASH).into_blocking_regions();
+ /// let flash = Mutex::new(RefCell::new(layout.bank1_region));
+ ///
+ /// let config = BootLoaderConfig::from_linkerfile_blocking(&flash, &flash, &flash);
+ /// // `config` can now be used to create a `BootLoader` instance for managing boot operations.
+ /// ```
+ /// Working examples can be found in the bootloader examples folder.
// #[cfg(target_os = "none")]
- pub fn from_linkerfile_blocking(flash: &'a Mutex>) -> Self {
+ pub fn from_linkerfile_blocking(
+ active_flash: &'a Mutex>,
+ dfu_flash: &'a Mutex>,
+ state_flash: &'a Mutex>,
+ ) -> Self {
extern "C" {
static __bootloader_state_start: u32;
static __bootloader_state_end: u32;
@@ -73,21 +108,21 @@ impl<'a, FLASH: NorFlash>
let end = &__bootloader_active_end as *const u32 as u32;
trace!("ACTIVE: 0x{:x} - 0x{:x}", start, end);
- BlockingPartition::new(flash, start, end - start)
+ BlockingPartition::new(active_flash, start, end - start)
};
let dfu = unsafe {
let start = &__bootloader_dfu_start as *const u32 as u32;
let end = &__bootloader_dfu_end as *const u32 as u32;
trace!("DFU: 0x{:x} - 0x{:x}", start, end);
- BlockingPartition::new(flash, start, end - start)
+ BlockingPartition::new(dfu_flash, start, end - start)
};
let state = unsafe {
let start = &__bootloader_state_start as *const u32 as u32;
let end = &__bootloader_state_end as *const u32 as u32;
trace!("STATE: 0x{:x} - 0x{:x}", start, end);
- BlockingPartition::new(flash, start, end - start)
+ BlockingPartition::new(state_flash, start, end - start)
};
Self { active, dfu, state }
@@ -135,51 +170,44 @@ impl BootLoader BootLoader Result {
// Ensure we have enough progress pages to store copy progress
@@ -224,6 +245,7 @@ impl BootLoader BootLoader(
) {
assert_eq!(active.capacity() as u32 % page_size, 0);
assert_eq!(dfu.capacity() as u32 % page_size, 0);
+ // DFU partition has to be bigger than ACTIVE partition to handle swap algorithm
assert!(dfu.capacity() as u32 - active.capacity() as u32 >= page_size);
assert!(2 + 2 * (active.capacity() as u32 / page_size) <= state.capacity() as u32 / STATE::WRITE_SIZE as u32);
}
diff --git a/embassy-boot/boot/src/digest_adapters/ed25519_dalek.rs b/embassy-boot/src/digest_adapters/ed25519_dalek.rs
similarity index 89%
rename from embassy-boot/boot/src/digest_adapters/ed25519_dalek.rs
rename to embassy-boot/src/digest_adapters/ed25519_dalek.rs
index a184d1c51..2e4e03da3 100644
--- a/embassy-boot/boot/src/digest_adapters/ed25519_dalek.rs
+++ b/embassy-boot/src/digest_adapters/ed25519_dalek.rs
@@ -1,6 +1,6 @@
use digest::typenum::U64;
use digest::{FixedOutput, HashMarker, OutputSizeUser, Update};
-use ed25519_dalek::Digest as _;
+use ed25519_dalek::Digest;
pub struct Sha512(ed25519_dalek::Sha512);
@@ -12,7 +12,7 @@ impl Default for Sha512 {
impl Update for Sha512 {
fn update(&mut self, data: &[u8]) {
- self.0.update(data)
+ Digest::update(&mut self.0, data)
}
}
diff --git a/embassy-boot/boot/src/digest_adapters/mod.rs b/embassy-boot/src/digest_adapters/mod.rs
similarity index 100%
rename from embassy-boot/boot/src/digest_adapters/mod.rs
rename to embassy-boot/src/digest_adapters/mod.rs
diff --git a/embassy-boot/boot/src/digest_adapters/salty.rs b/embassy-boot/src/digest_adapters/salty.rs
similarity index 100%
rename from embassy-boot/boot/src/digest_adapters/salty.rs
rename to embassy-boot/src/digest_adapters/salty.rs
diff --git a/embassy-boot/boot/src/firmware_updater/asynch.rs b/embassy-boot/src/firmware_updater/asynch.rs
similarity index 53%
rename from embassy-boot/boot/src/firmware_updater/asynch.rs
rename to embassy-boot/src/firmware_updater/asynch.rs
index ae713bb6f..26f65f295 100644
--- a/embassy-boot/boot/src/firmware_updater/asynch.rs
+++ b/embassy-boot/src/firmware_updater/asynch.rs
@@ -6,21 +6,25 @@ use embassy_sync::blocking_mutex::raw::NoopRawMutex;
use embedded_storage_async::nor_flash::NorFlash;
use super::FirmwareUpdaterConfig;
-use crate::{FirmwareUpdaterError, State, BOOT_MAGIC, STATE_ERASE_VALUE, SWAP_MAGIC};
+use crate::{FirmwareUpdaterError, State, BOOT_MAGIC, DFU_DETACH_MAGIC, STATE_ERASE_VALUE, SWAP_MAGIC};
/// FirmwareUpdater is an application API for interacting with the BootLoader without the ability to
/// 'mess up' the internal bootloader state
pub struct FirmwareUpdater<'d, DFU: NorFlash, STATE: NorFlash> {
dfu: DFU,
state: FirmwareState<'d, STATE>,
+ last_erased_dfu_sector_index: Option,
}
#[cfg(target_os = "none")]
-impl<'a, FLASH: NorFlash>
- FirmwareUpdaterConfig, Partition<'a, NoopRawMutex, FLASH>>
+impl<'a, DFU: NorFlash, STATE: NorFlash>
+ FirmwareUpdaterConfig, Partition<'a, NoopRawMutex, STATE>>
{
/// Create a firmware updater config from the flash and address symbols defined in the linkerfile
- pub fn from_linkerfile(flash: &'a embassy_sync::mutex::Mutex) -> Self {
+ pub fn from_linkerfile(
+ dfu_flash: &'a embassy_sync::mutex::Mutex,
+ state_flash: &'a embassy_sync::mutex::Mutex,
+ ) -> Self {
extern "C" {
static __bootloader_state_start: u32;
static __bootloader_state_end: u32;
@@ -33,14 +37,14 @@ impl<'a, FLASH: NorFlash>
let end = &__bootloader_dfu_end as *const u32 as u32;
trace!("DFU: 0x{:x} - 0x{:x}", start, end);
- Partition::new(flash, start, end - start)
+ Partition::new(dfu_flash, start, end - start)
};
let state = unsafe {
let start = &__bootloader_state_start as *const u32 as u32;
let end = &__bootloader_state_end as *const u32 as u32;
trace!("STATE: 0x{:x} - 0x{:x}", start, end);
- Partition::new(flash, start, end - start)
+ Partition::new(state_flash, start, end - start)
};
Self { dfu, state }
@@ -53,6 +57,7 @@ impl<'d, DFU: NorFlash, STATE: NorFlash> FirmwareUpdater<'d, DFU, STATE> {
Self {
dfu: config.dfu,
state: FirmwareState::new(config.state, aligned),
+ last_erased_dfu_sector_index: None,
}
}
@@ -69,7 +74,7 @@ impl<'d, DFU: NorFlash, STATE: NorFlash> FirmwareUpdater<'d, DFU, STATE> {
/// proceed with updating the firmware as it must be signed with a
/// corresponding private key (otherwise it could be malicious firmware).
///
- /// Mark to trigger firmware swap on next boot if verify suceeds.
+ /// Mark to trigger firmware swap on next boot if verify succeeds.
///
/// If the "ed25519-salty" feature is set (or another similar feature) then the signature is expected to have
/// been generated from a SHA-512 digest of the firmware bytes.
@@ -79,8 +84,8 @@ impl<'d, DFU: NorFlash, STATE: NorFlash> FirmwareUpdater<'d, DFU, STATE> {
#[cfg(feature = "_verify")]
pub async fn verify_and_mark_updated(
&mut self,
- _public_key: &[u8],
- _signature: &[u8],
+ _public_key: &[u8; 32],
+ _signature: &[u8; 64],
_update_len: u32,
) -> Result<(), FirmwareUpdaterError> {
assert!(_update_len <= self.dfu.capacity() as u32);
@@ -89,14 +94,14 @@ impl<'d, DFU: NorFlash, STATE: NorFlash> FirmwareUpdater<'d, DFU, STATE> {
#[cfg(feature = "ed25519-dalek")]
{
- use ed25519_dalek::{PublicKey, Signature, SignatureError, Verifier};
+ use ed25519_dalek::{Signature, SignatureError, Verifier, VerifyingKey};
use crate::digest_adapters::ed25519_dalek::Sha512;
let into_signature_error = |e: SignatureError| FirmwareUpdaterError::Signature(e.into());
- let public_key = PublicKey::from_bytes(_public_key).map_err(into_signature_error)?;
- let signature = Signature::from_bytes(_signature).map_err(into_signature_error)?;
+ let public_key = VerifyingKey::from_bytes(_public_key).map_err(into_signature_error)?;
+ let signature = Signature::from_bytes(_signature);
let mut chunk_buf = [0; 2];
let mut message = [0; 64];
@@ -106,7 +111,6 @@ impl<'d, DFU: NorFlash, STATE: NorFlash> FirmwareUpdater<'d, DFU, STATE> {
}
#[cfg(feature = "ed25519-salty")]
{
- use salty::constants::{PUBLICKEY_SERIALIZED_LENGTH, SIGNATURE_SERIALIZED_LENGTH};
use salty::{PublicKey, Signature};
use crate::digest_adapters::salty::Sha512;
@@ -115,10 +119,8 @@ impl<'d, DFU: NorFlash, STATE: NorFlash> FirmwareUpdater<'d, DFU, STATE> {
FirmwareUpdaterError::Signature(signature::Error::default())
}
- let public_key: [u8; PUBLICKEY_SERIALIZED_LENGTH] = _public_key.try_into().map_err(into_signature_error)?;
- let public_key = PublicKey::try_from(&public_key).map_err(into_signature_error)?;
- let signature: [u8; SIGNATURE_SERIALIZED_LENGTH] = _signature.try_into().map_err(into_signature_error)?;
- let signature = Signature::try_from(&signature).map_err(into_signature_error)?;
+ let public_key = PublicKey::try_from(_public_key).map_err(into_signature_error)?;
+ let signature = Signature::try_from(_signature).map_err(into_signature_error)?;
let mut message = [0; 64];
let mut chunk_buf = [0; 2];
@@ -161,26 +163,79 @@ impl<'d, DFU: NorFlash, STATE: NorFlash> FirmwareUpdater<'d, DFU, STATE> {
self.state.mark_updated().await
}
+ /// Mark to trigger USB DFU on next boot.
+ pub async fn mark_dfu(&mut self) -> Result<(), FirmwareUpdaterError> {
+ self.state.verify_booted().await?;
+ self.state.mark_dfu().await
+ }
+
/// Mark firmware boot successful and stop rollback on reset.
pub async fn mark_booted(&mut self) -> Result<(), FirmwareUpdaterError> {
self.state.mark_booted().await
}
- /// Write data to a flash page.
+ /// Writes firmware data to the device.
///
- /// The buffer must follow alignment requirements of the target flash and a multiple of page size big.
+ /// This function writes the given data to the firmware area starting at the specified offset.
+ /// It handles sector erasures and data writes while verifying the device is in a proper state
+ /// for firmware updates. The function ensures that only unerased sectors are erased before
+ /// writing and efficiently handles the writing process across sector boundaries and in
+ /// various configurations (data size, sector size, etc.).
///
- /// # Safety
+ /// # Arguments
///
- /// Failing to meet alignment and size requirements may result in a panic.
+ /// * `offset` - The starting offset within the firmware area where data writing should begin.
+ /// * `data` - A slice of bytes representing the firmware data to be written. It must be a
+ /// multiple of NorFlash WRITE_SIZE.
+ ///
+ /// # Returns
+ ///
+ /// A `Result<(), FirmwareUpdaterError>` indicating the success or failure of the write operation.
+ ///
+ /// # Errors
+ ///
+ /// This function will return an error if:
+ ///
+ /// - The device is not in a proper state to receive firmware updates (e.g., not booted).
+ /// - There is a failure erasing a sector before writing.
+ /// - There is a failure writing data to the device.
pub async fn write_firmware(&mut self, offset: usize, data: &[u8]) -> Result<(), FirmwareUpdaterError> {
- assert!(data.len() >= DFU::ERASE_SIZE);
-
+ // Make sure we are running a booted firmware to avoid reverting to a bad state.
self.state.verify_booted().await?;
- self.dfu.erase(offset as u32, (offset + data.len()) as u32).await?;
+ // Initialize variables to keep track of the remaining data and the current offset.
+ let mut remaining_data = data;
+ let mut offset = offset;
- self.dfu.write(offset as u32, data).await?;
+ // Continue writing as long as there is data left to write.
+ while !remaining_data.is_empty() {
+ // Compute the current sector and its boundaries.
+ let current_sector = offset / DFU::ERASE_SIZE;
+ let sector_start = current_sector * DFU::ERASE_SIZE;
+ let sector_end = sector_start + DFU::ERASE_SIZE;
+ // Determine if the current sector needs to be erased before writing.
+ let need_erase = self
+ .last_erased_dfu_sector_index
+ .map_or(true, |last_erased_sector| current_sector != last_erased_sector);
+
+ // If the sector needs to be erased, erase it and update the last erased sector index.
+ if need_erase {
+ self.dfu.erase(sector_start as u32, sector_end as u32).await?;
+ self.last_erased_dfu_sector_index = Some(current_sector);
+ }
+
+ // Calculate the size of the data chunk that can be written in the current iteration.
+ let write_size = core::cmp::min(remaining_data.len(), sector_end - offset);
+ // Split the data to get the current chunk to be written and the remaining data.
+ let (data_chunk, rest) = remaining_data.split_at(write_size);
+
+ // Write the current data chunk.
+ self.dfu.write(offset as u32, data_chunk).await?;
+
+ // Update the offset and remaining data for the next iteration.
+ remaining_data = rest;
+ offset += write_size;
+ }
Ok(())
}
@@ -207,14 +262,24 @@ pub struct FirmwareState<'d, STATE> {
}
impl<'d, STATE: NorFlash> FirmwareState<'d, STATE> {
- /// Create a firmware state instance with a buffer for magic content and state partition.
+ /// Create a firmware state instance from a FirmwareUpdaterConfig with a buffer for magic content and state partition.
///
/// # Safety
///
/// The `aligned` buffer must have a size of STATE::WRITE_SIZE, and follow the alignment rules for the flash being read from
/// and written to.
+ pub fn from_config(config: FirmwareUpdaterConfig, aligned: &'d mut [u8]) -> Self {
+ Self::new(config.state, aligned)
+ }
+
+ /// Create a firmware state instance with a buffer for magic content and state partition.
+ ///
+ /// # Safety
+ ///
+ /// The `aligned` buffer must have a size of maximum of STATE::WRITE_SIZE and STATE::READ_SIZE,
+ /// and follow the alignment rules for the flash being read from and written to.
pub fn new(state: STATE, aligned: &'d mut [u8]) -> Self {
- assert_eq!(aligned.len(), STATE::WRITE_SIZE);
+ assert_eq!(aligned.len(), STATE::WRITE_SIZE.max(STATE::READ_SIZE));
Self { state, aligned }
}
@@ -247,6 +312,11 @@ impl<'d, STATE: NorFlash> FirmwareState<'d, STATE> {
self.set_magic(SWAP_MAGIC).await
}
+ /// Mark to trigger USB DFU on next boot.
+ pub async fn mark_dfu(&mut self) -> Result<(), FirmwareUpdaterError> {
+ self.set_magic(DFU_DETACH_MAGIC).await
+ }
+
/// Mark firmware boot successful and stop rollback on reset.
pub async fn mark_booted(&mut self) -> Result<(), FirmwareUpdaterError> {
self.set_magic(BOOT_MAGIC).await
@@ -255,16 +325,25 @@ impl<'d, STATE: NorFlash> FirmwareState<'d, STATE> {
async fn set_magic(&mut self, magic: u8) -> Result<(), FirmwareUpdaterError> {
self.state.read(0, &mut self.aligned).await?;
- if self.aligned.iter().any(|&b| b != magic) {
+ if self.aligned[..STATE::WRITE_SIZE].iter().any(|&b| b != magic) {
// Read progress validity
- self.state.read(STATE::WRITE_SIZE as u32, &mut self.aligned).await?;
+ if STATE::READ_SIZE <= 2 * STATE::WRITE_SIZE {
+ self.state.read(STATE::WRITE_SIZE as u32, &mut self.aligned).await?;
+ } else {
+ self.aligned.rotate_left(STATE::WRITE_SIZE);
+ }
- if self.aligned.iter().any(|&b| b != STATE_ERASE_VALUE) {
+ if self.aligned[..STATE::WRITE_SIZE]
+ .iter()
+ .any(|&b| b != STATE_ERASE_VALUE)
+ {
// The current progress validity marker is invalid
} else {
// Invalidate progress
self.aligned.fill(!STATE_ERASE_VALUE);
- self.state.write(STATE::WRITE_SIZE as u32, &self.aligned).await?;
+ self.state
+ .write(STATE::WRITE_SIZE as u32, &self.aligned[..STATE::WRITE_SIZE])
+ .await?;
}
// Clear magic and progress
@@ -272,7 +351,7 @@ impl<'d, STATE: NorFlash> FirmwareState<'d, STATE> {
// Set magic
self.aligned.fill(magic);
- self.state.write(0, &self.aligned).await?;
+ self.state.write(0, &self.aligned[..STATE::WRITE_SIZE]).await?;
}
Ok(())
}
@@ -308,4 +387,76 @@ mod tests {
assert_eq!(Sha1::digest(update).as_slice(), hash);
}
+
+ #[test]
+ fn can_verify_sha1_sector_bigger_than_chunk() {
+ let flash = Mutex::::new(MemFlash::<131072, 4096, 8>::default());
+ let state = Partition::new(&flash, 0, 4096);
+ let dfu = Partition::new(&flash, 65536, 65536);
+ let mut aligned = [0; 8];
+
+ let update = [0x00, 0x11, 0x22, 0x33, 0x44, 0x55, 0x66];
+ let mut to_write = [0; 4096];
+ to_write[..7].copy_from_slice(update.as_slice());
+
+ let mut updater = FirmwareUpdater::new(FirmwareUpdaterConfig { dfu, state }, &mut aligned);
+ let mut offset = 0;
+ for chunk in to_write.chunks(1024) {
+ block_on(updater.write_firmware(offset, chunk)).unwrap();
+ offset += chunk.len();
+ }
+ let mut chunk_buf = [0; 2];
+ let mut hash = [0; 20];
+ block_on(updater.hash::(update.len() as u32, &mut chunk_buf, &mut hash)).unwrap();
+
+ assert_eq!(Sha1::digest(update).as_slice(), hash);
+ }
+
+ #[test]
+ fn can_verify_sha1_sector_smaller_than_chunk() {
+ let flash = Mutex::::new(MemFlash::<131072, 1024, 8>::default());
+ let state = Partition::new(&flash, 0, 4096);
+ let dfu = Partition::new(&flash, 65536, 65536);
+ let mut aligned = [0; 8];
+
+ let update = [0x00, 0x11, 0x22, 0x33, 0x44, 0x55, 0x66];
+ let mut to_write = [0; 4096];
+ to_write[..7].copy_from_slice(update.as_slice());
+
+ let mut updater = FirmwareUpdater::new(FirmwareUpdaterConfig { dfu, state }, &mut aligned);
+ let mut offset = 0;
+ for chunk in to_write.chunks(2048) {
+ block_on(updater.write_firmware(offset, chunk)).unwrap();
+ offset += chunk.len();
+ }
+ let mut chunk_buf = [0; 2];
+ let mut hash = [0; 20];
+ block_on(updater.hash::(update.len() as u32, &mut chunk_buf, &mut hash)).unwrap();
+
+ assert_eq!(Sha1::digest(update).as_slice(), hash);
+ }
+
+ #[test]
+ fn can_verify_sha1_cross_sector_boundary() {
+ let flash = Mutex::::new(MemFlash::<131072, 1024, 8>::default());
+ let state = Partition::new(&flash, 0, 4096);
+ let dfu = Partition::new(&flash, 65536, 65536);
+ let mut aligned = [0; 8];
+
+ let update = [0x00, 0x11, 0x22, 0x33, 0x44, 0x55, 0x66];
+ let mut to_write = [0; 4096];
+ to_write[..7].copy_from_slice(update.as_slice());
+
+ let mut updater = FirmwareUpdater::new(FirmwareUpdaterConfig { dfu, state }, &mut aligned);
+ let mut offset = 0;
+ for chunk in to_write.chunks(896) {
+ block_on(updater.write_firmware(offset, chunk)).unwrap();
+ offset += chunk.len();
+ }
+ let mut chunk_buf = [0; 2];
+ let mut hash = [0; 20];
+ block_on(updater.hash::(update.len() as u32, &mut chunk_buf, &mut hash)).unwrap();
+
+ assert_eq!(Sha1::digest(update).as_slice(), hash);
+ }
}
diff --git a/embassy-boot/boot/src/firmware_updater/blocking.rs b/embassy-boot/src/firmware_updater/blocking.rs
similarity index 50%
rename from embassy-boot/boot/src/firmware_updater/blocking.rs
rename to embassy-boot/src/firmware_updater/blocking.rs
index 76e4264a0..35772a856 100644
--- a/embassy-boot/boot/src/firmware_updater/blocking.rs
+++ b/embassy-boot/src/firmware_updater/blocking.rs
@@ -6,22 +6,54 @@ use embassy_sync::blocking_mutex::raw::NoopRawMutex;
use embedded_storage::nor_flash::NorFlash;
use super::FirmwareUpdaterConfig;
-use crate::{FirmwareUpdaterError, State, BOOT_MAGIC, STATE_ERASE_VALUE, SWAP_MAGIC};
+use crate::{FirmwareUpdaterError, State, BOOT_MAGIC, DFU_DETACH_MAGIC, STATE_ERASE_VALUE, SWAP_MAGIC};
/// Blocking FirmwareUpdater is an application API for interacting with the BootLoader without the ability to
/// 'mess up' the internal bootloader state
pub struct BlockingFirmwareUpdater<'d, DFU: NorFlash, STATE: NorFlash> {
dfu: DFU,
state: BlockingFirmwareState<'d, STATE>,
+ last_erased_dfu_sector_index: Option,
}
#[cfg(target_os = "none")]
-impl<'a, FLASH: NorFlash>
- FirmwareUpdaterConfig, BlockingPartition<'a, NoopRawMutex, FLASH>>
+impl<'a, DFU: NorFlash, STATE: NorFlash>
+ FirmwareUpdaterConfig, BlockingPartition<'a, NoopRawMutex, STATE>>
{
- /// Create a firmware updater config from the flash and address symbols defined in the linkerfile
+ /// Constructs a `FirmwareUpdaterConfig` instance from flash memory and address symbols defined in the linker file.
+ ///
+ /// This method initializes `BlockingPartition` instances for the DFU (Device Firmware Update), and state
+ /// partitions, leveraging start and end addresses specified by the linker. These partitions are critical
+ /// for managing firmware updates, application state, and boot operations within the bootloader.
+ ///
+ /// # Parameters
+ /// - `dfu_flash`: A reference to a mutex-protected `RefCell` for the DFU partition's flash interface.
+ /// - `state_flash`: A reference to a mutex-protected `RefCell` for the state partition's flash interface.
+ ///
+ /// # Safety
+ /// The method contains `unsafe` blocks for dereferencing raw pointers that represent the start and end addresses
+ /// of the bootloader's partitions in flash memory. It is crucial that these addresses are accurately defined
+ /// in the memory.x file to prevent undefined behavior.
+ ///
+ /// The caller must ensure that the memory regions defined by these symbols are valid and that the flash memory
+ /// interfaces provided are compatible with these regions.
+ ///
+ /// # Returns
+ /// A `FirmwareUpdaterConfig` instance with `BlockingPartition` instances for the DFU, and state partitions.
+ ///
+ /// # Example
+ /// ```ignore
+ /// // Assume `dfu_flash`, and `state_flash` share the same flash memory interface.
+ /// let layout = Flash::new_blocking(p.FLASH).into_blocking_regions();
+ /// let flash = Mutex::new(RefCell::new(layout.bank1_region));
+ ///
+ /// let config = FirmwareUpdaterConfig::from_linkerfile_blocking(&flash, &flash);
+ /// // `config` can now be used to create a `FirmwareUpdater` instance for managing boot operations.
+ /// ```
+ /// Working examples can be found in the bootloader examples folder.
pub fn from_linkerfile_blocking(
- flash: &'a embassy_sync::blocking_mutex::Mutex>,
+ dfu_flash: &'a embassy_sync::blocking_mutex::Mutex>,
+ state_flash: &'a embassy_sync::blocking_mutex::Mutex>,
) -> Self {
extern "C" {
static __bootloader_state_start: u32;
@@ -35,14 +67,14 @@ impl<'a, FLASH: NorFlash>
let end = &__bootloader_dfu_end as *const u32 as u32;
trace!("DFU: 0x{:x} - 0x{:x}", start, end);
- BlockingPartition::new(flash, start, end - start)
+ BlockingPartition::new(dfu_flash, start, end - start)
};
let state = unsafe {
let start = &__bootloader_state_start as *const u32 as u32;
let end = &__bootloader_state_end as *const u32 as u32;
trace!("STATE: 0x{:x} - 0x{:x}", start, end);
- BlockingPartition::new(flash, start, end - start)
+ BlockingPartition::new(state_flash, start, end - start)
};
Self { dfu, state }
@@ -60,6 +92,7 @@ impl<'d, DFU: NorFlash, STATE: NorFlash> BlockingFirmwareUpdater<'d, DFU, STATE>
Self {
dfu: config.dfu,
state: BlockingFirmwareState::new(config.state, aligned),
+ last_erased_dfu_sector_index: None,
}
}
@@ -76,7 +109,7 @@ impl<'d, DFU: NorFlash, STATE: NorFlash> BlockingFirmwareUpdater<'d, DFU, STATE>
/// proceed with updating the firmware as it must be signed with a
/// corresponding private key (otherwise it could be malicious firmware).
///
- /// Mark to trigger firmware swap on next boot if verify suceeds.
+ /// Mark to trigger firmware swap on next boot if verify succeeds.
///
/// If the "ed25519-salty" feature is set (or another similar feature) then the signature is expected to have
/// been generated from a SHA-512 digest of the firmware bytes.
@@ -86,8 +119,8 @@ impl<'d, DFU: NorFlash, STATE: NorFlash> BlockingFirmwareUpdater<'d, DFU, STATE>
#[cfg(feature = "_verify")]
pub fn verify_and_mark_updated(
&mut self,
- _public_key: &[u8],
- _signature: &[u8],
+ _public_key: &[u8; 32],
+ _signature: &[u8; 64],
_update_len: u32,
) -> Result<(), FirmwareUpdaterError> {
assert!(_update_len <= self.dfu.capacity() as u32);
@@ -96,14 +129,14 @@ impl<'d, DFU: NorFlash, STATE: NorFlash> BlockingFirmwareUpdater<'d, DFU, STATE>
#[cfg(feature = "ed25519-dalek")]
{
- use ed25519_dalek::{PublicKey, Signature, SignatureError, Verifier};
+ use ed25519_dalek::{Signature, SignatureError, Verifier, VerifyingKey};
use crate::digest_adapters::ed25519_dalek::Sha512;
let into_signature_error = |e: SignatureError| FirmwareUpdaterError::Signature(e.into());
- let public_key = PublicKey::from_bytes(_public_key).map_err(into_signature_error)?;
- let signature = Signature::from_bytes(_signature).map_err(into_signature_error)?;
+ let public_key = VerifyingKey::from_bytes(_public_key).map_err(into_signature_error)?;
+ let signature = Signature::from_bytes(_signature);
let mut message = [0; 64];
let mut chunk_buf = [0; 2];
@@ -113,7 +146,6 @@ impl<'d, DFU: NorFlash, STATE: NorFlash> BlockingFirmwareUpdater<'d, DFU, STATE>
}
#[cfg(feature = "ed25519-salty")]
{
- use salty::constants::{PUBLICKEY_SERIALIZED_LENGTH, SIGNATURE_SERIALIZED_LENGTH};
use salty::{PublicKey, Signature};
use crate::digest_adapters::salty::Sha512;
@@ -122,10 +154,8 @@ impl<'d, DFU: NorFlash, STATE: NorFlash> BlockingFirmwareUpdater<'d, DFU, STATE>
FirmwareUpdaterError::Signature(signature::Error::default())
}
- let public_key: [u8; PUBLICKEY_SERIALIZED_LENGTH] = _public_key.try_into().map_err(into_signature_error)?;
- let public_key = PublicKey::try_from(&public_key).map_err(into_signature_error)?;
- let signature: [u8; SIGNATURE_SERIALIZED_LENGTH] = _signature.try_into().map_err(into_signature_error)?;
- let signature = Signature::try_from(&signature).map_err(into_signature_error)?;
+ let public_key = PublicKey::try_from(_public_key).map_err(into_signature_error)?;
+ let signature = Signature::try_from(_signature).map_err(into_signature_error)?;
let mut message = [0; 64];
let mut chunk_buf = [0; 2];
@@ -168,25 +198,79 @@ impl<'d, DFU: NorFlash, STATE: NorFlash> BlockingFirmwareUpdater<'d, DFU, STATE>
self.state.mark_updated()
}
+ /// Mark to trigger USB DFU device on next boot.
+ pub fn mark_dfu(&mut self) -> Result<(), FirmwareUpdaterError> {
+ self.state.verify_booted()?;
+ self.state.mark_dfu()
+ }
+
/// Mark firmware boot successful and stop rollback on reset.
pub fn mark_booted(&mut self) -> Result<(), FirmwareUpdaterError> {
self.state.mark_booted()
}
- /// Write data to a flash page.
+ /// Writes firmware data to the device.
///
- /// The buffer must follow alignment requirements of the target flash and a multiple of page size big.
+ /// This function writes the given data to the firmware area starting at the specified offset.
+ /// It handles sector erasures and data writes while verifying the device is in a proper state
+ /// for firmware updates. The function ensures that only unerased sectors are erased before
+ /// writing and efficiently handles the writing process across sector boundaries and in
+ /// various configurations (data size, sector size, etc.).
///
- /// # Safety
+ /// # Arguments
///
- /// Failing to meet alignment and size requirements may result in a panic.
+ /// * `offset` - The starting offset within the firmware area where data writing should begin.
+ /// * `data` - A slice of bytes representing the firmware data to be written. It must be a
+ /// multiple of NorFlash WRITE_SIZE.
+ ///
+ /// # Returns
+ ///
+ /// A `Result<(), FirmwareUpdaterError>` indicating the success or failure of the write operation.
+ ///
+ /// # Errors
+ ///
+ /// This function will return an error if:
+ ///
+ /// - The device is not in a proper state to receive firmware updates (e.g., not booted).
+ /// - There is a failure erasing a sector before writing.
+ /// - There is a failure writing data to the device.
pub fn write_firmware(&mut self, offset: usize, data: &[u8]) -> Result<(), FirmwareUpdaterError> {
- assert!(data.len() >= DFU::ERASE_SIZE);
+ // Make sure we are running a booted firmware to avoid reverting to a bad state.
self.state.verify_booted()?;
- self.dfu.erase(offset as u32, (offset + data.len()) as u32)?;
+ // Initialize variables to keep track of the remaining data and the current offset.
+ let mut remaining_data = data;
+ let mut offset = offset;
- self.dfu.write(offset as u32, data)?;
+ // Continue writing as long as there is data left to write.
+ while !remaining_data.is_empty() {
+ // Compute the current sector and its boundaries.
+ let current_sector = offset / DFU::ERASE_SIZE;
+ let sector_start = current_sector * DFU::ERASE_SIZE;
+ let sector_end = sector_start + DFU::ERASE_SIZE;
+ // Determine if the current sector needs to be erased before writing.
+ let need_erase = self
+ .last_erased_dfu_sector_index
+ .map_or(true, |last_erased_sector| current_sector != last_erased_sector);
+
+ // If the sector needs to be erased, erase it and update the last erased sector index.
+ if need_erase {
+ self.dfu.erase(sector_start as u32, sector_end as u32)?;
+ self.last_erased_dfu_sector_index = Some(current_sector);
+ }
+
+ // Calculate the size of the data chunk that can be written in the current iteration.
+ let write_size = core::cmp::min(remaining_data.len(), sector_end - offset);
+ // Split the data to get the current chunk to be written and the remaining data.
+ let (data_chunk, rest) = remaining_data.split_at(write_size);
+
+ // Write the current data chunk.
+ self.dfu.write(offset as u32, data_chunk)?;
+
+ // Update the offset and remaining data for the next iteration.
+ remaining_data = rest;
+ offset += write_size;
+ }
Ok(())
}
@@ -213,6 +297,16 @@ pub struct BlockingFirmwareState<'d, STATE> {
}
impl<'d, STATE: NorFlash> BlockingFirmwareState<'d, STATE> {
+ /// Creates a firmware state instance from a FirmwareUpdaterConfig, with a buffer for magic content and state partition.
+ ///
+ /// # Safety
+ ///
+ /// The `aligned` buffer must have a size of STATE::WRITE_SIZE, and follow the alignment rules for the flash being read from
+ /// and written to.
+ pub fn from_config(config: FirmwareUpdaterConfig, aligned: &'d mut [u8]) -> Self {
+ Self::new(config.state, aligned)
+ }
+
/// Create a firmware state instance with a buffer for magic content and state partition.
///
/// # Safety
@@ -226,7 +320,7 @@ impl<'d, STATE: NorFlash> BlockingFirmwareState<'d, STATE> {
// Make sure we are running a booted firmware to avoid reverting to a bad state.
fn verify_booted(&mut self) -> Result<(), FirmwareUpdaterError> {
- if self.get_state()? == State::Boot {
+ if self.get_state()? == State::Boot || self.get_state()? == State::DfuDetach {
Ok(())
} else {
Err(FirmwareUpdaterError::BadState)
@@ -243,6 +337,8 @@ impl<'d, STATE: NorFlash> BlockingFirmwareState<'d, STATE> {
if !self.aligned.iter().any(|&b| b != SWAP_MAGIC) {
Ok(State::Swap)
+ } else if !self.aligned.iter().any(|&b| b != DFU_DETACH_MAGIC) {
+ Ok(State::DfuDetach)
} else {
Ok(State::Boot)
}
@@ -253,6 +349,11 @@ impl<'d, STATE: NorFlash> BlockingFirmwareState<'d, STATE> {
self.set_magic(SWAP_MAGIC)
}
+ /// Mark to trigger USB DFU on next boot.
+ pub fn mark_dfu(&mut self) -> Result<(), FirmwareUpdaterError> {
+ self.set_magic(DFU_DETACH_MAGIC)
+ }
+
/// Mark firmware boot successful and stop rollback on reset.
pub fn mark_booted(&mut self) -> Result<(), FirmwareUpdaterError> {
self.set_magic(BOOT_MAGIC)
@@ -317,4 +418,82 @@ mod tests {
assert_eq!(Sha1::digest(update).as_slice(), hash);
}
+
+ #[test]
+ fn can_verify_sha1_sector_bigger_than_chunk() {
+ let flash = Mutex::::new(RefCell::new(MemFlash::<131072, 4096, 8>::default()));
+ let state = BlockingPartition::new(&flash, 0, 4096);
+ let dfu = BlockingPartition::new(&flash, 65536, 65536);
+ let mut aligned = [0; 8];
+
+ let update = [0x00, 0x11, 0x22, 0x33, 0x44, 0x55, 0x66];
+ let mut to_write = [0; 4096];
+ to_write[..7].copy_from_slice(update.as_slice());
+
+ let mut updater = BlockingFirmwareUpdater::new(FirmwareUpdaterConfig { dfu, state }, &mut aligned);
+ let mut offset = 0;
+ for chunk in to_write.chunks(1024) {
+ updater.write_firmware(offset, chunk).unwrap();
+ offset += chunk.len();
+ }
+ let mut chunk_buf = [0; 2];
+ let mut hash = [0; 20];
+ updater
+ .hash::(update.len() as u32, &mut chunk_buf, &mut hash)
+ .unwrap();
+
+ assert_eq!(Sha1::digest(update).as_slice(), hash);
+ }
+
+ #[test]
+ fn can_verify_sha1_sector_smaller_than_chunk() {
+ let flash = Mutex::::new(RefCell::new(MemFlash::<131072, 1024, 8>::default()));
+ let state = BlockingPartition::new(&flash, 0, 4096);
+ let dfu = BlockingPartition::new(&flash, 65536, 65536);
+ let mut aligned = [0; 8];
+
+ let update = [0x00, 0x11, 0x22, 0x33, 0x44, 0x55, 0x66];
+ let mut to_write = [0; 4096];
+ to_write[..7].copy_from_slice(update.as_slice());
+
+ let mut updater = BlockingFirmwareUpdater::new(FirmwareUpdaterConfig { dfu, state }, &mut aligned);
+ let mut offset = 0;
+ for chunk in to_write.chunks(2048) {
+ updater.write_firmware(offset, chunk).unwrap();
+ offset += chunk.len();
+ }
+ let mut chunk_buf = [0; 2];
+ let mut hash = [0; 20];
+ updater
+ .hash::(update.len() as u32, &mut chunk_buf, &mut hash)
+ .unwrap();
+
+ assert_eq!(Sha1::digest(update).as_slice(), hash);
+ }
+
+ #[test]
+ fn can_verify_sha1_cross_sector_boundary() {
+ let flash = Mutex::::new(RefCell::new(MemFlash::<131072, 1024, 8>::default()));
+ let state = BlockingPartition::new(&flash, 0, 4096);
+ let dfu = BlockingPartition::new(&flash, 65536, 65536);
+ let mut aligned = [0; 8];
+
+ let update = [0x00, 0x11, 0x22, 0x33, 0x44, 0x55, 0x66];
+ let mut to_write = [0; 4096];
+ to_write[..7].copy_from_slice(update.as_slice());
+
+ let mut updater = BlockingFirmwareUpdater::new(FirmwareUpdaterConfig { dfu, state }, &mut aligned);
+ let mut offset = 0;
+ for chunk in to_write.chunks(896) {
+ updater.write_firmware(offset, chunk).unwrap();
+ offset += chunk.len();
+ }
+ let mut chunk_buf = [0; 2];
+ let mut hash = [0; 20];
+ updater
+ .hash::(update.len() as u32, &mut chunk_buf, &mut hash)
+ .unwrap();
+
+ assert_eq!(Sha1::digest(update).as_slice(), hash);
+ }
}
diff --git a/embassy-boot/boot/src/firmware_updater/mod.rs b/embassy-boot/src/firmware_updater/mod.rs
similarity index 93%
rename from embassy-boot/boot/src/firmware_updater/mod.rs
rename to embassy-boot/src/firmware_updater/mod.rs
index 4814786bf..4c4f4f10b 100644
--- a/embassy-boot/boot/src/firmware_updater/mod.rs
+++ b/embassy-boot/src/firmware_updater/mod.rs
@@ -8,7 +8,7 @@ use embedded_storage::nor_flash::{NorFlashError, NorFlashErrorKind};
/// Firmware updater flash configuration holding the two flashes used by the updater
///
/// If only a single flash is actually used, then that flash should be partitioned into two partitions before use.
-/// The easiest way to do this is to use [`FirmwareUpdaterConfig::from_linkerfile`] or [`FirmwareUpdaterConfig::from_linkerfile_blocking`] which will partition
+/// The easiest way to do this is to use [`FirmwareUpdaterConfig::from_linkerfile_blocking`] or [`FirmwareUpdaterConfig::from_linkerfile_blocking`] which will partition
/// the provided flash according to symbols defined in the linkerfile.
pub struct FirmwareUpdaterConfig {
/// The dfu flash partition
diff --git a/embassy-boot/boot/src/fmt.rs b/embassy-boot/src/fmt.rs
similarity index 99%
rename from embassy-boot/boot/src/fmt.rs
rename to embassy-boot/src/fmt.rs
index 78e583c1c..2ac42c557 100644
--- a/embassy-boot/boot/src/fmt.rs
+++ b/embassy-boot/src/fmt.rs
@@ -1,5 +1,5 @@
#![macro_use]
-#![allow(unused_macros)]
+#![allow(unused)]
use core::fmt::{Debug, Display, LowerHex};
@@ -229,7 +229,6 @@ impl Try for Result {
}
}
-#[allow(unused)]
pub(crate) struct Bytes<'a>(pub &'a [u8]);
impl<'a> Debug for Bytes<'a> {
diff --git a/embassy-boot/boot/src/lib.rs b/embassy-boot/src/lib.rs
similarity index 96%
rename from embassy-boot/boot/src/lib.rs
rename to embassy-boot/src/lib.rs
index 9e70a4dca..b4f03e01e 100644
--- a/embassy-boot/boot/src/lib.rs
+++ b/embassy-boot/src/lib.rs
@@ -23,6 +23,7 @@ pub use firmware_updater::{
pub(crate) const BOOT_MAGIC: u8 = 0xD0;
pub(crate) const SWAP_MAGIC: u8 = 0xF0;
+pub(crate) const DFU_DETACH_MAGIC: u8 = 0xE0;
/// The state of the bootloader after running prepare.
#[derive(PartialEq, Eq, Debug)]
@@ -32,6 +33,8 @@ pub enum State {
Boot,
/// Bootloader has swapped the active partition with the dfu partition and will attempt boot.
Swap,
+ /// Application has received a request to reboot into DFU mode to apply an update.
+ DfuDetach,
}
/// Buffer aligned to 32 byte boundary, largest known alignment requirement for embassy-boot.
@@ -272,21 +275,19 @@ mod tests {
// The following key setup is based on:
// https://docs.rs/ed25519-dalek/latest/ed25519_dalek/#example
- use ed25519_dalek::Keypair;
+ use ed25519_dalek::{Digest, Sha512, Signature, Signer, SigningKey, VerifyingKey};
use rand::rngs::OsRng;
let mut csprng = OsRng {};
- let keypair: Keypair = Keypair::generate(&mut csprng);
+ let keypair = SigningKey::generate(&mut csprng);
- use ed25519_dalek::{Digest, Sha512, Signature, Signer};
let firmware: &[u8] = b"This are bytes that would otherwise be firmware bytes for DFU.";
let mut digest = Sha512::new();
digest.update(&firmware);
let message = digest.finalize();
let signature: Signature = keypair.sign(&message);
- use ed25519_dalek::PublicKey;
- let public_key: PublicKey = keypair.public;
+ let public_key = keypair.verifying_key();
// Setup flash
let flash = BlockingTestFlash::new(BootLoaderConfig {
diff --git a/embassy-boot/boot/src/mem_flash.rs b/embassy-boot/src/mem_flash.rs
similarity index 100%
rename from embassy-boot/boot/src/mem_flash.rs
rename to embassy-boot/src/mem_flash.rs
diff --git a/embassy-boot/boot/src/test_flash/asynch.rs b/embassy-boot/src/test_flash/asynch.rs
similarity index 100%
rename from embassy-boot/boot/src/test_flash/asynch.rs
rename to embassy-boot/src/test_flash/asynch.rs
diff --git a/embassy-boot/boot/src/test_flash/blocking.rs b/embassy-boot/src/test_flash/blocking.rs
similarity index 100%
rename from embassy-boot/boot/src/test_flash/blocking.rs
rename to embassy-boot/src/test_flash/blocking.rs
diff --git a/embassy-boot/boot/src/test_flash/mod.rs b/embassy-boot/src/test_flash/mod.rs
similarity index 100%
rename from embassy-boot/boot/src/test_flash/mod.rs
rename to embassy-boot/src/test_flash/mod.rs
diff --git a/embassy-boot/stm32/README.md b/embassy-boot/stm32/README.md
deleted file mode 100644
index b4d7ba5a4..000000000
--- a/embassy-boot/stm32/README.md
+++ /dev/null
@@ -1,24 +0,0 @@
-# embassy-boot-stm32
-
-An [Embassy](https://embassy.dev) project.
-
-An adaptation of `embassy-boot` for STM32.
-
-## Features
-
-* Configure bootloader partitions based on linker script.
-* Load applications from active partition.
-
-## Minimum supported Rust version (MSRV)
-
-`embassy-boot-stm32` is guaranteed to compile on the latest stable Rust version at the time of release. It might compile with older versions but that may change in any new patch release.
-
-## License
-
-This work is licensed under either of
-
-- Apache License, Version 2.0 ([LICENSE-APACHE](LICENSE-APACHE) or
- )
-- MIT license ([LICENSE-MIT](LICENSE-MIT) or )
-
-at your option.
diff --git a/embassy-embedded-hal/Cargo.toml b/embassy-embedded-hal/Cargo.toml
index 2a0b25479..e89179740 100644
--- a/embassy-embedded-hal/Cargo.toml
+++ b/embassy-embedded-hal/Cargo.toml
@@ -3,7 +3,14 @@ name = "embassy-embedded-hal"
version = "0.1.0"
edition = "2021"
license = "MIT OR Apache-2.0"
-
+description = "Collection of utilities to use `embedded-hal` and `embedded-storage` traits with Embassy."
+repository = "https://github.com/embassy-rs/embassy"
+documentation = "https://docs.embassy.dev/embassy-embedded-hal"
+categories = [
+ "embedded",
+ "no-std",
+ "asynchronous",
+]
[package.metadata.embassy_docs]
src_base = "https://github.com/embassy-rs/embassy/blob/embassy-embedded-hal-v$VERSION/embassy-embedded-hal/src/"
@@ -11,6 +18,9 @@ src_base_git = "https://github.com/embassy-rs/embassy/blob/$COMMIT/embassy-embed
features = ["std"]
target = "x86_64-unknown-linux-gnu"
+[package.metadata.docs.rs]
+features = ["std"]
+
[features]
std = []
time = ["dep:embassy-time"]
@@ -19,12 +29,12 @@ default = ["time"]
[dependencies]
embassy-futures = { version = "0.1.0", path = "../embassy-futures" }
embassy-sync = { version = "0.5.0", path = "../embassy-sync" }
-embassy-time = { version = "0.2", path = "../embassy-time", optional = true }
+embassy-time = { version = "0.3.0", path = "../embassy-time", optional = true }
embedded-hal-02 = { package = "embedded-hal", version = "0.2.6", features = [
"unproven",
] }
-embedded-hal-1 = { package = "embedded-hal", version = "=1.0.0-rc.2" }
-embedded-hal-async = { version = "=1.0.0-rc.2" }
+embedded-hal-1 = { package = "embedded-hal", version = "1.0" }
+embedded-hal-async = { version = "1.0" }
embedded-storage = "0.3.1"
embedded-storage-async = { version = "0.4.1" }
nb = "1.0.0"
diff --git a/embassy-embedded-hal/README.md b/embassy-embedded-hal/README.md
new file mode 100644
index 000000000..69581c788
--- /dev/null
+++ b/embassy-embedded-hal/README.md
@@ -0,0 +1,12 @@
+# embassy-embedded-hal
+
+Collection of utilities to use `embedded-hal` and `embedded-storage` traits with Embassy.
+
+- Shared SPI and I2C buses, both blocking and async, with a `SetConfig` trait allowing changing bus configuration (e.g. frequency) between devices on the same bus.
+- Async utilities
+ - Adapters to convert from blocking to (fake) async.
+ - Adapters to insert yields on trait operations.
+- Flash utilities
+ - Split a flash memory into smaller partitions.
+ - Concatenate flash memories together.
+ - Simulated in-memory flash.
diff --git a/embassy-embedded-hal/build.rs b/embassy-embedded-hal/build.rs
deleted file mode 100644
index 78bd27ec7..000000000
--- a/embassy-embedded-hal/build.rs
+++ /dev/null
@@ -1,18 +0,0 @@
-use std::env;
-use std::ffi::OsString;
-use std::process::Command;
-
-fn main() {
- println!("cargo:rerun-if-changed=build.rs");
-
- let rustc = env::var_os("RUSTC").unwrap_or_else(|| OsString::from("rustc"));
-
- let output = Command::new(rustc)
- .arg("--version")
- .output()
- .expect("failed to run `rustc --version`");
-
- if String::from_utf8_lossy(&output.stdout).contains("nightly") {
- println!("cargo:rustc-cfg=nightly");
- }
-}
diff --git a/embassy-embedded-hal/src/adapter/blocking_async.rs b/embassy-embedded-hal/src/adapter/blocking_async.rs
index ae0d0a7f9..bafc31583 100644
--- a/embassy-embedded-hal/src/adapter/blocking_async.rs
+++ b/embassy-embedded-hal/src/adapter/blocking_async.rs
@@ -104,8 +104,10 @@ where
}
/// NOR flash wrapper
-use embedded_storage::nor_flash::{ErrorType, NorFlash, ReadNorFlash};
-use embedded_storage_async::nor_flash::{NorFlash as AsyncNorFlash, ReadNorFlash as AsyncReadNorFlash};
+use embedded_storage::nor_flash::{ErrorType, MultiwriteNorFlash, NorFlash, ReadNorFlash};
+use embedded_storage_async::nor_flash::{
+ MultiwriteNorFlash as AsyncMultiwriteNorFlash, NorFlash as AsyncNorFlash, ReadNorFlash as AsyncReadNorFlash,
+};
impl ErrorType for BlockingAsync
where
@@ -143,3 +145,5 @@ where
self.wrapped.capacity()
}
}
+
+impl AsyncMultiwriteNorFlash for BlockingAsync where T: MultiwriteNorFlash {}
diff --git a/embassy-embedded-hal/src/lib.rs b/embassy-embedded-hal/src/lib.rs
index b40f892f4..99a2d93c7 100644
--- a/embassy-embedded-hal/src/lib.rs
+++ b/embassy-embedded-hal/src/lib.rs
@@ -1,10 +1,7 @@
#![cfg_attr(not(feature = "std"), no_std)]
-#![cfg_attr(nightly, feature(async_fn_in_trait, impl_trait_projections))]
-#![cfg_attr(nightly, allow(stable_features, unknown_lints))]
#![allow(async_fn_in_trait)]
#![warn(missing_docs)]
-
-//! Utilities to use `embedded-hal` traits with Embassy.
+#![doc = include_str!("../README.md")]
pub mod adapter;
pub mod flash;
diff --git a/embassy-embedded-hal/src/shared_bus/asynch/i2c.rs b/embassy-embedded-hal/src/shared_bus/asynch/i2c.rs
index 779c04263..71ce09def 100644
--- a/embassy-embedded-hal/src/shared_bus/asynch/i2c.rs
+++ b/embassy-embedded-hal/src/shared_bus/asynch/i2c.rs
@@ -106,6 +106,11 @@ impl<'a, M: RawMutex, BUS: SetConfig> I2cDeviceWithConfig<'a, M, BUS> {
pub fn new(bus: &'a Mutex, config: BUS::Config) -> Self {
Self { bus, config }
}
+
+ /// Change the device's config at runtime
+ pub fn set_config(&mut self, config: BUS::Config) {
+ self.config = config;
+ }
}
impl<'a, M, BUS> i2c::ErrorType for I2cDeviceWithConfig<'a, M, BUS>
diff --git a/embassy-embedded-hal/src/shared_bus/asynch/spi.rs b/embassy-embedded-hal/src/shared_bus/asynch/spi.rs
index 62b2c92a0..9890f218d 100644
--- a/embassy-embedded-hal/src/shared_bus/asynch/spi.rs
+++ b/embassy-embedded-hal/src/shared_bus/asynch/spi.rs
@@ -122,6 +122,11 @@ impl<'a, M: RawMutex, BUS: SetConfig, CS> SpiDeviceWithConfig<'a, M, BUS, CS> {
pub fn new(bus: &'a Mutex, cs: CS, config: BUS::Config) -> Self {
Self { bus, cs, config }
}
+
+ /// Change the device's config at runtime
+ pub fn set_config(&mut self, config: BUS::Config) {
+ self.config = config;
+ }
}
impl<'a, M, BUS, CS> spi::ErrorType for SpiDeviceWithConfig<'a, M, BUS, CS>
diff --git a/embassy-embedded-hal/src/shared_bus/blocking/i2c.rs b/embassy-embedded-hal/src/shared_bus/blocking/i2c.rs
index 233c9e1fd..627767c8a 100644
--- a/embassy-embedded-hal/src/shared_bus/blocking/i2c.rs
+++ b/embassy-embedded-hal/src/shared_bus/blocking/i2c.rs
@@ -67,9 +67,11 @@ where
}
fn transaction<'a>(&mut self, address: u8, operations: &mut [Operation<'a>]) -> Result<(), Self::Error> {
- let _ = address;
- let _ = operations;
- todo!()
+ self.bus.lock(|bus| {
+ bus.borrow_mut()
+ .transaction(address, operations)
+ .map_err(I2cDeviceError::I2c)
+ })
}
}
@@ -130,6 +132,11 @@ impl<'a, M: RawMutex, BUS: SetConfig> I2cDeviceWithConfig<'a, M, BUS> {
pub fn new(bus: &'a Mutex>, config: BUS::Config) -> Self {
Self { bus, config }
}
+
+ /// Change the device's config at runtime
+ pub fn set_config(&mut self, config: BUS::Config) {
+ self.config = config;
+ }
}
impl<'a, M, BUS> ErrorType for I2cDeviceWithConfig<'a, M, BUS>
@@ -171,8 +178,10 @@ where
}
fn transaction<'a>(&mut self, address: u8, operations: &mut [Operation<'a>]) -> Result<(), Self::Error> {
- let _ = address;
- let _ = operations;
- todo!()
+ self.bus.lock(|bus| {
+ let mut bus = bus.borrow_mut();
+ bus.set_config(&self.config).map_err(|_| I2cDeviceError::Config)?;
+ bus.transaction(address, operations).map_err(I2cDeviceError::I2c)
+ })
}
}
diff --git a/embassy-embedded-hal/src/shared_bus/blocking/spi.rs b/embassy-embedded-hal/src/shared_bus/blocking/spi.rs
index 59b65bfbd..801899f9f 100644
--- a/embassy-embedded-hal/src/shared_bus/blocking/spi.rs
+++ b/embassy-embedded-hal/src/shared_bus/blocking/spi.rs
@@ -147,6 +147,11 @@ impl<'a, M: RawMutex, BUS: SetConfig, CS> SpiDeviceWithConfig<'a, M, BUS, CS> {
pub fn new(bus: &'a Mutex>, cs: CS, config: BUS::Config) -> Self {
Self { bus, cs, config }
}
+
+ /// Change the device's config at runtime
+ pub fn set_config(&mut self, config: BUS::Config) {
+ self.config = config;
+ }
}
impl<'a, M, BUS, CS> spi::ErrorType for SpiDeviceWithConfig<'a, M, BUS, CS>
diff --git a/embassy-executor-macros/Cargo.toml b/embassy-executor-macros/Cargo.toml
index 6ea7ddb71..2953e7ccc 100644
--- a/embassy-executor-macros/Cargo.toml
+++ b/embassy-executor-macros/Cargo.toml
@@ -1,10 +1,11 @@
[package]
name = "embassy-executor-macros"
-version = "0.4.0"
+version = "0.4.1"
edition = "2021"
license = "MIT OR Apache-2.0"
description = "macros for creating the entry point and tasks for embassy-executor"
repository = "https://github.com/embassy-rs/embassy"
+documentation = "https://docs.embassy.dev/embassy-executor-macros"
categories = [
"embedded",
"no-std",
@@ -21,4 +22,4 @@ proc-macro2 = "1.0.29"
proc-macro = true
[features]
-nightly = []
\ No newline at end of file
+nightly = []
diff --git a/embassy-executor-macros/README.md b/embassy-executor-macros/README.md
index a959c85d5..3a8d49aa1 100644
--- a/embassy-executor-macros/README.md
+++ b/embassy-executor-macros/README.md
@@ -3,13 +3,3 @@
An [Embassy](https://embassy.dev) project.
NOTE: Do not use this crate directly. The macros are re-exported by `embassy-executor`.
-
-## License
-
-This work is licensed under either of
-
-- Apache License, Version 2.0 ([LICENSE-APACHE](LICENSE-APACHE) or
- )
-- MIT license ([LICENSE-MIT](LICENSE-MIT) or )
-
-at your option.
diff --git a/embassy-executor-macros/src/lib.rs b/embassy-executor-macros/src/lib.rs
index c9d58746a..5461fe04c 100644
--- a/embassy-executor-macros/src/lib.rs
+++ b/embassy-executor-macros/src/lib.rs
@@ -62,6 +62,13 @@ pub fn task(args: TokenStream, item: TokenStream) -> TokenStream {
task::run(&args.meta, f).unwrap_or_else(|x| x).into()
}
+#[proc_macro_attribute]
+pub fn main_avr(args: TokenStream, item: TokenStream) -> TokenStream {
+ let args = syn::parse_macro_input!(args as Args);
+ let f = syn::parse_macro_input!(item as syn::ItemFn);
+ main::run(&args.meta, f, main::avr()).unwrap_or_else(|x| x).into()
+}
+
/// Creates a new `executor` instance and declares an application entry point for Cortex-M spawning the corresponding function body as an async task.
///
/// The following restrictions apply:
diff --git a/embassy-executor-macros/src/macros/main.rs b/embassy-executor-macros/src/macros/main.rs
index 3c0d58567..088e64d1c 100644
--- a/embassy-executor-macros/src/macros/main.rs
+++ b/embassy-executor-macros/src/macros/main.rs
@@ -12,6 +12,20 @@ struct Args {
entry: Option,
}
+pub fn avr() -> TokenStream {
+ quote! {
+ #[avr_device::entry]
+ fn main() -> ! {
+ let mut executor = ::embassy_executor::Executor::new();
+ let executor = unsafe { __make_static(&mut executor) };
+
+ executor.run(|spawner| {
+ spawner.must_spawn(__embassy_main(spawner));
+ })
+ }
+ }
+}
+
pub fn riscv(args: &[NestedMeta]) -> TokenStream {
let maybe_entry = match Args::from_list(args) {
Ok(args) => args.entry,
diff --git a/embassy-executor-macros/src/macros/task.rs b/embassy-executor-macros/src/macros/task.rs
index 5161e1020..96c6267b2 100644
--- a/embassy-executor-macros/src/macros/task.rs
+++ b/embassy-executor-macros/src/macros/task.rs
@@ -49,7 +49,7 @@ pub fn run(args: &[NestedMeta], f: syn::ItemFn) -> Result Result match t.pat.as_mut() {
syn::Pat::Ident(id) => {
- arg_names.push(id.ident.clone());
id.mutability = None;
+ args.push((id.clone(), t.attrs.clone()));
}
_ => {
ctxt.error_spanned_by(arg, "pattern matching in task arguments is not yet supported");
@@ -79,13 +79,35 @@ pub fn run(args: &[NestedMeta], f: syn::ItemFn) -> Result ::embassy_executor::SpawnToken {
- type Fut = impl ::core::future::Future + 'static;
+ trait _EmbassyInternalTaskTrait {
+ type Fut: ::core::future::Future + 'static;
+ fn construct(#fargs) -> Self::Fut;
+ }
+
+ impl _EmbassyInternalTaskTrait for () {
+ type Fut = impl core::future::Future + 'static;
+ fn construct(#fargs) -> Self::Fut {
+ #task_inner_ident(#(#full_args,)*)
+ }
+ }
+
const POOL_SIZE: usize = #pool_size;
- static POOL: ::embassy_executor::raw::TaskPool = ::embassy_executor::raw::TaskPool::new();
- unsafe { POOL._spawn_async_fn(move || #task_inner_ident(#(#arg_names,)*)) }
+ static POOL: ::embassy_executor::raw::TaskPool<<() as _EmbassyInternalTaskTrait>::Fut, POOL_SIZE> = ::embassy_executor::raw::TaskPool::new();
+ unsafe { POOL._spawn_async_fn(move || <() as _EmbassyInternalTaskTrait>::construct(#(#full_args,)*)) }
}
};
#[cfg(not(feature = "nightly"))]
@@ -93,7 +115,7 @@ pub fn run(args: &[NestedMeta], f: syn::ItemFn) -> Result ::embassy_executor::SpawnToken {
const POOL_SIZE: usize = #pool_size;
static POOL: ::embassy_executor::_export::TaskPoolRef = ::embassy_executor::_export::TaskPoolRef::new();
- unsafe { POOL.get::<_, POOL_SIZE>()._spawn_async_fn(move || #task_inner_ident(#(#arg_names,)*)) }
+ unsafe { POOL.get::<_, POOL_SIZE>()._spawn_async_fn(move || #task_inner_ident(#(#full_args,)*)) }
}
};
diff --git a/embassy-executor-macros/src/util/ctxt.rs b/embassy-executor-macros/src/util/ctxt.rs
index 74c872c3c..9c78cda01 100644
--- a/embassy-executor-macros/src/util/ctxt.rs
+++ b/embassy-executor-macros/src/util/ctxt.rs
@@ -7,7 +7,6 @@ use std::thread;
use proc_macro2::TokenStream;
use quote::{quote, ToTokens};
-use syn;
/// A type to collect errors together and format them.
///
diff --git a/embassy-executor/CHANGELOG.md b/embassy-executor/CHANGELOG.md
index 5c6749230..77c64fd8e 100644
--- a/embassy-executor/CHANGELOG.md
+++ b/embassy-executor/CHANGELOG.md
@@ -7,6 +7,10 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
## Unreleased
+## 0.5.0 - 2024-01-11
+
+- Updated to `embassy-time-driver 0.1`, `embassy-time-queue-driver 0.1`, compatible with `embassy-time v0.3` and higher.
+
## 0.4.0 - 2023-12-05
- Removed `arch-xtensa`. Use the executor provided by the HAL crate (`esp-hal`, `esp32s3-hal`, etc...) instead.
diff --git a/embassy-executor/Cargo.toml b/embassy-executor/Cargo.toml
index ec5aca46d..431165cee 100644
--- a/embassy-executor/Cargo.toml
+++ b/embassy-executor/Cargo.toml
@@ -1,10 +1,11 @@
[package]
name = "embassy-executor"
-version = "0.4.0"
+version = "0.5.0"
edition = "2021"
license = "MIT OR Apache-2.0"
description = "async/await executor designed for embedded usage"
repository = "https://github.com/embassy-rs/embassy"
+documentation = "https://docs.embassy.dev/embassy-executor"
categories = [
"embedded",
"no-std",
@@ -14,7 +15,7 @@ categories = [
[package.metadata.embassy_docs]
src_base = "https://github.com/embassy-rs/embassy/blob/embassy-executor-v$VERSION/embassy-executor/src/"
src_base_git = "https://github.com/embassy-rs/embassy/blob/$COMMIT/embassy-executor/src/"
-features = ["nightly", "defmt"]
+features = ["defmt"]
flavors = [
{ name = "std", target = "x86_64-unknown-linux-gnu", features = ["arch-std", "executor-thread"] },
{ name = "wasm", target = "wasm32-unknown-unknown", features = ["arch-wasm", "executor-thread"] },
@@ -25,7 +26,7 @@ flavors = [
[package.metadata.docs.rs]
default-target = "thumbv7em-none-eabi"
targets = ["thumbv7em-none-eabi"]
-features = ["nightly", "defmt", "arch-cortex-m", "executor-thread", "executor-interrupt"]
+features = ["defmt", "arch-cortex-m", "executor-thread", "executor-interrupt"]
[dependencies]
defmt = { version = "0.3", optional = true }
@@ -33,11 +34,13 @@ log = { version = "0.4.14", optional = true }
rtos-trace = { version = "0.1.2", optional = true }
embassy-executor-macros = { version = "0.4.0", path = "../embassy-executor-macros" }
-embassy-time = { version = "0.2", path = "../embassy-time", optional = true}
+embassy-time-driver = { version = "0.1.0", path = "../embassy-time-driver", optional = true }
+embassy-time-queue-driver = { version = "0.1.0", path = "../embassy-time-queue-driver", optional = true }
critical-section = "1.1"
-# needed for riscv
-# remove when https://github.com/rust-lang/rust/pull/114499 is merged
+document-features = "0.2.7"
+
+# needed for AVR
portable-atomic = { version = "1.5", optional = true }
# arch-cortex-m dependencies
@@ -47,72 +50,137 @@ cortex-m = { version = "0.7.6", optional = true }
wasm-bindgen = { version = "0.2.82", optional = true }
js-sys = { version = "0.3", optional = true }
+# arch-avr dependencies
+avr-device = { version = "0.5.3", optional = true }
+
[dev-dependencies]
critical-section = { version = "1.1", features = ["std"] }
[features]
-# Architecture
-_arch = [] # some arch was picked
-arch-std = ["_arch", "critical-section/std"]
-arch-cortex-m = ["_arch", "dep:cortex-m"]
-arch-riscv32 = ["_arch", "dep:portable-atomic"]
-arch-wasm = ["_arch", "dep:wasm-bindgen", "dep:js-sys"]
-
-# Enable the thread-mode executor (using WFE/SEV in Cortex-M, WFI in other embedded archs)
-executor-thread = []
-# Enable the interrupt-mode executor (available in Cortex-M only)
-executor-interrupt = []
-
-# Enable nightly-only features
+## Enable nightly-only features
nightly = ["embassy-executor-macros/nightly"]
+# Enables turbo wakers, which requires patching core. Not surfaced in the docs by default due to
+# being an complicated advanced and undocumented feature.
+# See: https://github.com/embassy-rs/embassy/pull/1263
turbowakers = []
-integrated-timers = ["dep:embassy-time"]
+## Use the executor-integrated `embassy-time` timer queue.
+integrated-timers = ["dep:embassy-time-driver", "dep:embassy-time-queue-driver"]
+
+#! ### Architecture
+_arch = [] # some arch was picked
+## std
+arch-std = ["_arch", "critical-section/std"]
+## Cortex-M
+arch-cortex-m = ["_arch", "dep:cortex-m"]
+## RISC-V 32
+arch-riscv32 = ["_arch"]
+## WASM
+arch-wasm = ["_arch", "dep:wasm-bindgen", "dep:js-sys"]
+## AVR
+arch-avr = ["_arch", "dep:portable-atomic", "dep:avr-device"]
+
+#! ### Executor
+
+## Enable the thread-mode executor (using WFE/SEV in Cortex-M, WFI in other embedded archs)
+executor-thread = []
+## Enable the interrupt-mode executor (available in Cortex-M only)
+executor-interrupt = []
+
+#! ### Task Arena Size
+#! Sets the [task arena](#task-arena) size. Necessary if you’re not using `nightly`.
+#!
+#!
+#! Preconfigured Task Arena Sizes:
+#!
+#!
# BEGIN AUTOGENERATED CONFIG FEATURES
# Generated by gen_config.py. DO NOT EDIT.
+## 64
task-arena-size-64 = []
+## 128
task-arena-size-128 = []
+## 192
task-arena-size-192 = []
+## 256
task-arena-size-256 = []
+## 320
task-arena-size-320 = []
+## 384
task-arena-size-384 = []
+## 512
task-arena-size-512 = []
+## 640
task-arena-size-640 = []
+## 768
task-arena-size-768 = []
+## 1024
task-arena-size-1024 = []
+## 1280
task-arena-size-1280 = []
+## 1536
task-arena-size-1536 = []
+## 2048
task-arena-size-2048 = []
+## 2560
task-arena-size-2560 = []
+## 3072
task-arena-size-3072 = []
+## 4096 (default)
task-arena-size-4096 = [] # Default
+## 5120
task-arena-size-5120 = []
+## 6144
task-arena-size-6144 = []
+## 8192
task-arena-size-8192 = []
+## 10240
task-arena-size-10240 = []
+## 12288
task-arena-size-12288 = []
+## 16384
task-arena-size-16384 = []
+## 20480
task-arena-size-20480 = []
+## 24576
task-arena-size-24576 = []
+## 32768
task-arena-size-32768 = []
+## 40960
task-arena-size-40960 = []
+## 49152
task-arena-size-49152 = []
+## 65536
task-arena-size-65536 = []
+## 81920
task-arena-size-81920 = []
+## 98304
task-arena-size-98304 = []
+## 131072
task-arena-size-131072 = []
+## 163840
task-arena-size-163840 = []
+## 196608
task-arena-size-196608 = []
+## 262144
task-arena-size-262144 = []
+## 327680
task-arena-size-327680 = []
+## 393216
task-arena-size-393216 = []
+## 524288
task-arena-size-524288 = []
+## 655360
task-arena-size-655360 = []
+## 786432
task-arena-size-786432 = []
+## 1048576
task-arena-size-1048576 = []
# END AUTOGENERATED CONFIG FEATURES
+
+#!
diff --git a/embassy-executor/README.md b/embassy-executor/README.md
index 80ecfc71a..aa9d59907 100644
--- a/embassy-executor/README.md
+++ b/embassy-executor/README.md
@@ -22,7 +22,7 @@ Tasks are allocated from the arena when spawned for the first time. If the task
The arena size can be configured in two ways:
- Via Cargo features: enable a Cargo feature like `task-arena-size-8192`. Only a selection of values
- is available, check `Cargo.toml` for the list.
+ is available, see [Task Area Sizes](#task-arena-size) for reference.
- Via environment variables at build time: set the variable named `EMBASSY_EXECUTOR_TASK_ARENA_SIZE`. For example
`EMBASSY_EXECUTOR_TASK_ARENA_SIZE=4321 cargo build`. You can also set them in the `[env]` section of `.cargo/config.toml`.
Any value can be set, unlike with Cargo features.
diff --git a/embassy-executor/gen_config.py b/embassy-executor/gen_config.py
index e427d29f4..cf32bd530 100644
--- a/embassy-executor/gen_config.py
+++ b/embassy-executor/gen_config.py
@@ -45,6 +45,12 @@ things = ""
for f in features:
name = f["name"].replace("_", "-")
for val in f["vals"]:
+ things += f"## {val}"
+ if val == f["default"]:
+ things += " (default)\n"
+ else:
+ things += "\n"
+
things += f"{name}-{val} = []"
if val == f["default"]:
things += " # Default"
diff --git a/embassy-executor/src/arch/avr.rs b/embassy-executor/src/arch/avr.rs
new file mode 100644
index 000000000..70085d04d
--- /dev/null
+++ b/embassy-executor/src/arch/avr.rs
@@ -0,0 +1,72 @@
+#[cfg(feature = "executor-interrupt")]
+compile_error!("`executor-interrupt` is not supported with `arch-avr`.");
+
+#[cfg(feature = "executor-thread")]
+pub use thread::*;
+#[cfg(feature = "executor-thread")]
+mod thread {
+ use core::marker::PhantomData;
+
+ pub use embassy_executor_macros::main_avr as main;
+ use portable_atomic::{AtomicBool, Ordering};
+
+ use crate::{raw, Spawner};
+
+ static SIGNAL_WORK_THREAD_MODE: AtomicBool = AtomicBool::new(false);
+
+ #[export_name = "__pender"]
+ fn __pender(_context: *mut ()) {
+ SIGNAL_WORK_THREAD_MODE.store(true, Ordering::SeqCst);
+ }
+
+ /// avr Executor
+ pub struct Executor {
+ inner: raw::Executor,
+ not_send: PhantomData<*mut ()>,
+ }
+
+ impl Executor {
+ /// Create a new Executor.
+ pub fn new() -> Self {
+ Self {
+ inner: raw::Executor::new(core::ptr::null_mut()),
+ not_send: PhantomData,
+ }
+ }
+
+ /// Run the executor.
+ ///
+ /// The `init` closure is called with a [`Spawner`] that spawns tasks on
+ /// this executor. Use it to spawn the initial task(s). After `init` returns,
+ /// the executor starts running the tasks.
+ ///
+ /// To spawn more tasks later, you may keep copies of the [`Spawner`] (it is `Copy`),
+ /// for example by passing it as an argument to the initial tasks.
+ ///
+ /// This function requires `&'static mut self`. This means you have to store the
+ /// Executor instance in a place where it'll live forever and grants you mutable
+ /// access. There's a few ways to do this:
+ ///
+ /// - a [StaticCell](https://docs.rs/static_cell/latest/static_cell/) (safe)
+ /// - a `static mut` (unsafe)
+ /// - a local variable in a function you know never returns (like `fn main() -> !`), upgrading its lifetime with `transmute`. (unsafe)
+ ///
+ /// This function never returns.
+ pub fn run(&'static mut self, init: impl FnOnce(Spawner)) -> ! {
+ init(self.inner.spawner());
+
+ loop {
+ unsafe {
+ avr_device::interrupt::disable();
+ if !SIGNAL_WORK_THREAD_MODE.swap(false, Ordering::SeqCst) {
+ avr_device::interrupt::enable();
+ avr_device::asm::sleep();
+ } else {
+ avr_device::interrupt::enable();
+ self.inner.poll();
+ }
+ }
+ }
+ }
+ }
+}
diff --git a/embassy-executor/src/arch/riscv32.rs b/embassy-executor/src/arch/riscv32.rs
index c56f502d3..01e63a9fd 100644
--- a/embassy-executor/src/arch/riscv32.rs
+++ b/embassy-executor/src/arch/riscv32.rs
@@ -6,9 +6,9 @@ pub use thread::*;
#[cfg(feature = "executor-thread")]
mod thread {
use core::marker::PhantomData;
+ use core::sync::atomic::{AtomicBool, Ordering};
pub use embassy_executor_macros::main_riscv as main;
- use portable_atomic::{AtomicBool, Ordering};
use crate::{raw, Spawner};
diff --git a/embassy-executor/src/fmt.rs b/embassy-executor/src/fmt.rs
index 78e583c1c..2ac42c557 100644
--- a/embassy-executor/src/fmt.rs
+++ b/embassy-executor/src/fmt.rs
@@ -1,5 +1,5 @@
#![macro_use]
-#![allow(unused_macros)]
+#![allow(unused)]
use core::fmt::{Debug, Display, LowerHex};
@@ -229,7 +229,6 @@ impl Try for Result {
}
}
-#[allow(unused)]
pub(crate) struct Bytes<'a>(pub &'a [u8]);
impl<'a> Debug for Bytes<'a> {
diff --git a/embassy-executor/src/lib.rs b/embassy-executor/src/lib.rs
index 4c6900a6d..6a2e493a2 100644
--- a/embassy-executor/src/lib.rs
+++ b/embassy-executor/src/lib.rs
@@ -3,6 +3,9 @@
#![doc = include_str!("../README.md")]
#![warn(missing_docs)]
+//! ## Feature flags
+#![doc = document_features::document_features!(feature_label = r#"{feature}"#)]
+
// This mod MUST go first, so that the others see its macros.
pub(crate) mod fmt;
@@ -20,9 +23,10 @@ macro_rules! check_at_most_one {
check_at_most_one!(@amo [$($f)*] [$($f)*] []);
};
}
-check_at_most_one!("arch-cortex-m", "arch-riscv32", "arch-std", "arch-wasm",);
+check_at_most_one!("arch-avr", "arch-cortex-m", "arch-riscv32", "arch-std", "arch-wasm",);
#[cfg(feature = "_arch")]
+#[cfg_attr(feature = "arch-avr", path = "arch/avr.rs")]
#[cfg_attr(feature = "arch-cortex-m", path = "arch/cortex_m.rs")]
#[cfg_attr(feature = "arch-riscv32", path = "arch/riscv32.rs")]
#[cfg_attr(feature = "arch-std", path = "arch/std.rs")]
diff --git a/embassy-executor/src/raw/mod.rs b/embassy-executor/src/raw/mod.rs
index b16a1c7c3..d9ea5c005 100644
--- a/embassy-executor/src/raw/mod.rs
+++ b/embassy-executor/src/raw/mod.rs
@@ -30,9 +30,7 @@ use core::ptr::NonNull;
use core::task::{Context, Poll};
#[cfg(feature = "integrated-timers")]
-use embassy_time::driver::{self, AlarmHandle};
-#[cfg(feature = "integrated-timers")]
-use embassy_time::Instant;
+use embassy_time_driver::AlarmHandle;
#[cfg(feature = "rtos-trace")]
use rtos_trace::trace;
@@ -50,7 +48,7 @@ pub(crate) struct TaskHeader {
poll_fn: SyncUnsafeCell