From be184a552d77111538008feeb3e24bde3688412e Mon Sep 17 00:00:00 2001 From: Scott Mabin Date: Mon, 22 Aug 2022 12:02:28 -0700 Subject: [PATCH] `critical_section` implementations & esp_backtrace (#151) * CS impl * use CS Mutex in C3 examples * use CS Mutex in S2 examples * Update esp32 example * run fmt * Update S3 examples * Remove uses of unsafe where no longer required * use esp_backtrace in examples * fix import & fmt once more * Bump MSRV to 1.60.0 Co-authored-by: Jesse Braham --- .github/workflows/ci.yml | 4 +- README.md | 4 +- esp-hal-common/Cargo.toml | 10 +- esp-hal-common/src/clocks_ll/esp32.rs | 6 +- esp-hal-common/src/clocks_ll/esp32c3.rs | 13 +- esp-hal-common/src/gpio.rs | 11 +- esp-hal-common/src/ledc/timer.rs | 3 +- esp-hal-common/src/lib.rs | 118 +++++++++++++++++++ esp-hal-common/src/rtc/esp32.rs | 8 +- esp-hal-common/src/rtc/esp32c3.rs | 11 +- esp-hal-common/src/rtc/esp32s2.rs | 8 +- esp-hal-common/src/rtc/esp32s3.rs | 8 +- esp-hal-common/src/rtc_cntl.rs | 73 ++++++------ esp-hal-common/src/spi.rs | 66 ++++++----- esp32-hal/Cargo.toml | 3 +- esp32-hal/examples/adc.rs | 2 +- esp32-hal/examples/advanced_serial.rs | 2 +- esp32-hal/examples/blinky.rs | 2 +- esp32-hal/examples/clock_monitor.rs | 33 +++--- esp32-hal/examples/dac.rs | 2 +- esp32-hal/examples/gpio_interrupt.rs | 38 +++--- esp32-hal/examples/hello_rgb.rs | 2 +- esp32-hal/examples/hello_world.rs | 2 +- esp32-hal/examples/i2c_display.rs | 2 +- esp32-hal/examples/ledc.rs | 2 +- esp32-hal/examples/multicore.rs | 19 ++- esp32-hal/examples/pulse_control.rs | 2 +- esp32-hal/examples/ram.rs | 2 +- esp32-hal/examples/read_efuse.rs | 2 +- esp32-hal/examples/rtc_watchdog.rs | 34 ++---- esp32-hal/examples/serial_interrupts.rs | 61 +++++----- esp32-hal/examples/spi_eh1_loopback.rs | 15 +-- esp32-hal/examples/spi_loopback.rs | 2 +- esp32-hal/examples/timer_interrupt.rs | 133 ++++++++------------- esp32-hal/examples/watchdog.rs | 2 +- esp32c3-hal/Cargo.toml | 4 +- esp32c3-hal/examples/adc.rs | 2 +- esp32c3-hal/examples/advanced_serial.rs | 2 +- esp32c3-hal/examples/blinky.rs | 2 +- esp32c3-hal/examples/clock_monitor.rs | 21 ++-- esp32c3-hal/examples/gpio_interrupt.rs | 20 ++-- esp32c3-hal/examples/hello_rgb.rs | 2 +- esp32c3-hal/examples/hello_world.rs | 2 +- esp32c3-hal/examples/i2c_display.rs | 2 +- esp32c3-hal/examples/ledc.rs | 2 +- esp32c3-hal/examples/pulse_control.rs | 2 +- esp32c3-hal/examples/ram.rs | 2 +- esp32c3-hal/examples/read_efuse.rs | 2 +- esp32c3-hal/examples/rtc_watchdog.rs | 14 +-- esp32c3-hal/examples/serial_interrupts.rs | 21 ++-- esp32c3-hal/examples/spi_eh1_loopback.rs | 15 +-- esp32c3-hal/examples/spi_loopback.rs | 2 +- esp32c3-hal/examples/systimer.rs | 117 ++++++++---------- esp32c3-hal/examples/timer_interrupt.rs | 22 ++-- esp32c3-hal/examples/usb_serial_jtag.rs | 2 +- esp32c3-hal/examples/watchdog.rs | 2 +- esp32s2-hal/Cargo.toml | 3 +- esp32s2-hal/examples/adc.rs | 2 +- esp32s2-hal/examples/advanced_serial.rs | 2 +- esp32s2-hal/examples/blinky.rs | 2 +- esp32s2-hal/examples/clock_monitor.rs | 33 +++--- esp32s2-hal/examples/dac.rs | 2 +- esp32s2-hal/examples/gpio_interrupt.rs | 34 +++--- esp32s2-hal/examples/hello_rgb.rs | 2 +- esp32s2-hal/examples/hello_world.rs | 2 +- esp32s2-hal/examples/i2c_display.rs | 2 +- esp32s2-hal/examples/ledc.rs | 2 +- esp32s2-hal/examples/pulse_control.rs | 2 +- esp32s2-hal/examples/ram.rs | 2 +- esp32s2-hal/examples/read_efuse.rs | 2 +- esp32s2-hal/examples/rtc_watchdog.rs | 34 ++---- esp32s2-hal/examples/serial_interrupts.rs | 61 +++++----- esp32s2-hal/examples/spi_eh1_loopback.rs | 2 +- esp32s2-hal/examples/spi_loopback.rs | 2 +- esp32s2-hal/examples/systimer.rs | 68 +++++------ esp32s2-hal/examples/timer_interrupt.rs | 137 ++++++++-------------- esp32s2-hal/examples/watchdog.rs | 2 +- esp32s3-hal/Cargo.toml | 2 + esp32s3-hal/examples/advanced_serial.rs | 2 +- esp32s3-hal/examples/blinky.rs | 2 +- esp32s3-hal/examples/clock_monitor.rs | 36 +++--- esp32s3-hal/examples/gpio_interrupt.rs | 33 +++--- esp32s3-hal/examples/hello_rgb.rs | 2 +- esp32s3-hal/examples/hello_world.rs | 2 +- esp32s3-hal/examples/i2c_display.rs | 2 +- esp32s3-hal/examples/ledc.rs | 4 +- esp32s3-hal/examples/multicore.rs | 19 ++- esp32s3-hal/examples/pulse_control.rs | 2 +- esp32s3-hal/examples/ram.rs | 2 +- esp32s3-hal/examples/read_efuse.rs | 2 +- esp32s3-hal/examples/rtc_watchdog.rs | 37 +++--- esp32s3-hal/examples/serial_interrupts.rs | 61 +++++----- esp32s3-hal/examples/spi_eh1_loopback.rs | 15 +-- esp32s3-hal/examples/spi_loopback.rs | 2 +- esp32s3-hal/examples/systimer.rs | 74 ++++++------ esp32s3-hal/examples/timer_interrupt.rs | 137 ++++++++-------------- esp32s3-hal/examples/usb_serial_jtag.rs | 2 +- esp32s3-hal/examples/watchdog.rs | 2 +- 98 files changed, 856 insertions(+), 947 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 8c97e097a..3cb82e3ee 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -118,7 +118,7 @@ jobs: with: profile: minimal target: riscv32imc-unknown-none-elf - toolchain: "1.59.0" + toolchain: "1.60.0" default: true - uses: Swatinem/rust-cache@v1 - uses: actions-rs/cargo@v1 @@ -140,7 +140,7 @@ jobs: default: true ldproxy: false buildtargets: ${{ matrix.chip }} - version: "1.59.0" + version: "1.60.0" - uses: Swatinem/rust-cache@v1 - uses: actions-rs/cargo@v1 with: diff --git a/README.md b/README.md index 8b466b4f0..4bf029376 100644 --- a/README.md +++ b/README.md @@ -36,8 +36,8 @@ _\* via [atomic emulation]_ The **M**inimum **S**upported **R**ust **V**ersions are: -- `1.59.0` for RISC-V devices (**ESP32-C3**) -- `1.59.0` for Xtensa devices (**ESP32**, **ESP32-S2**, **ESP32-S3**) +- `1.60.0` for RISC-V devices (**ESP32-C3**) +- `1.60.0` for Xtensa devices (**ESP32**, **ESP32-S2**, **ESP32-S3**) Note that targeting the Xtensa ISA requires the use of the [esp-rs/rust] compiler fork, whereas RISC-V is officially supported by the official Rust compiler. diff --git a/esp-hal-common/Cargo.toml b/esp-hal-common/Cargo.toml index 4554a0ee2..3e943160b 100644 --- a/esp-hal-common/Cargo.toml +++ b/esp-hal-common/Cargo.toml @@ -34,6 +34,8 @@ ufmt-write = { version = "0.1", optional = true } # Smart-LED (e.g., WS2812/SK68XX) support smart-leds-trait = { version = "0.2.1", optional = true } +critical-section = "1.0.0" + # IMPORTANT: # Each supported device MUST have its PAC included below along with a # corresponding feature. We rename the PAC packages because we cannot @@ -46,10 +48,10 @@ esp32s2_pac = { package = "esp32s2", version = "0.3.0", optional = true } esp32s3_pac = { package = "esp32s3", version = "0.3.0", optional = true } [features] -esp32 = ["esp32_pac/rt" , "procmacros/xtensa", "multi_core" , "xtensa-lx-rt/esp32", "xtensa-lx/esp32"] -esp32c3 = ["esp32c3_pac/rt", "procmacros/riscv" , "single_core", "riscv", "riscv-atomic-emulation-trap"] -esp32s2 = ["esp32s2_pac/rt", "procmacros/xtensa", "single_core", "xtensa-lx-rt/esp32s2", "xtensa-lx/esp32s2"] -esp32s3 = ["esp32s3_pac/rt", "procmacros/xtensa", "multi_core" , "xtensa-lx-rt/esp32s3", "xtensa-lx/esp32s3"] +esp32 = ["esp32_pac/rt" , "procmacros/xtensa", "multi_core" , "xtensa-lx-rt/esp32", "xtensa-lx/esp32", "critical-section/restore-state-u32"] +esp32c3 = ["esp32c3_pac/rt", "procmacros/riscv" , "single_core", "riscv", "riscv-atomic-emulation-trap", "critical-section/restore-state-u8"] +esp32s2 = ["esp32s2_pac/rt", "procmacros/xtensa", "single_core", "xtensa-lx-rt/esp32s2", "xtensa-lx/esp32s2", "critical-section/restore-state-u32"] +esp32s3 = ["esp32s3_pac/rt", "procmacros/xtensa", "multi_core" , "xtensa-lx-rt/esp32s3", "xtensa-lx/esp32s3", "critical-section/restore-state-u32"] # Core Count (should not be enabled directly, but instead by a PAC's feature) single_core = [] diff --git a/esp-hal-common/src/clocks_ll/esp32.rs b/esp-hal-common/src/clocks_ll/esp32.rs index 5be4060a9..6f5ea116e 100644 --- a/esp-hal-common/src/clocks_ll/esp32.rs +++ b/esp-hal-common/src/clocks_ll/esp32.rs @@ -1,8 +1,4 @@ -use crate::clock::{ - Clock, - XtalClock, - PllClock, -}; +use crate::clock::{Clock, PllClock, XtalClock}; const REF_CLK_FREQ: u32 = 1000000; diff --git a/esp-hal-common/src/clocks_ll/esp32c3.rs b/esp-hal-common/src/clocks_ll/esp32c3.rs index c5d3e849c..5c5a05f6b 100644 --- a/esp-hal-common/src/clocks_ll/esp32c3.rs +++ b/esp-hal-common/src/clocks_ll/esp32c3.rs @@ -1,9 +1,11 @@ use paste::paste; -use crate::clock::{ApbClock, Clock, CpuClock, PllClock, XtalClock}; - -use crate::rom::{ets_update_cpu_frequency, regi2c_ctrl_write_reg, regi2c_ctrl_write_reg_mask}; -use crate::{regi2c_write, regi2c_write_mask}; +use crate::{ + clock::{ApbClock, Clock, CpuClock, PllClock, XtalClock}, + regi2c_write, + regi2c_write_mask, + rom::{ets_update_cpu_frequency, regi2c_ctrl_write_reg, regi2c_ctrl_write_reg_mask}, +}; const I2C_BBPLL: u32 = 0x66; const I2C_BBPLL_HOSTID: u32 = 0; @@ -188,7 +190,8 @@ pub(crate) fn esp32c3_rtc_update_to_xtal(freq: XtalClock, _div: u32) { unsafe { ets_update_cpu_frequency(freq.mhz()); - // Set divider from XTAL to APB clock. Need to set divider to 1 (reg. value 0) first. + // Set divider from XTAL to APB clock. Need to set divider to 1 (reg. value 0) + // first. system_control.sysclk_conf.modify(|_, w| { w.pre_div_cnt() .bits(0) diff --git a/esp-hal-common/src/gpio.rs b/esp-hal-common/src/gpio.rs index 7c46a82b0..2470c060e 100644 --- a/esp-hal-common/src/gpio.rs +++ b/esp-hal-common/src/gpio.rs @@ -142,8 +142,9 @@ pub trait InputPin: Pin { /// Remove a connected `signal` from this input pin. /// - /// Clears the entry in the GPIO matrix / IO mux that associates this input pin with the given - /// [input `signal`](`InputSignal`). Any other connected signals remain intact. + /// Clears the entry in the GPIO matrix / IO mux that associates this input + /// pin with the given [input `signal`](`InputSignal`). Any other + /// connected signals remain intact. fn disconnect_input_from_peripheral(&mut self, signal: InputSignal) -> &mut Self; } @@ -181,9 +182,9 @@ pub trait OutputPin: Pin { /// Remove this output pin from a connected [signal](`InputSignal`). /// - /// Clears the entry in the GPIO matrix / IO mux that associates this output pin with a - /// previously connected [signal](`InputSignal`). Any other outputs connected to the signal - /// remain intact. + /// Clears the entry in the GPIO matrix / IO mux that associates this output + /// pin with a previously connected [signal](`InputSignal`). Any other + /// outputs connected to the signal remain intact. fn disconnect_peripheral_from_output(&mut self) -> &mut Self; fn internal_pull_up(&mut self, on: bool) -> &mut Self; diff --git a/esp-hal-common/src/ledc/timer.rs b/esp-hal-common/src/ledc/timer.rs index 19484a401..f620f0797 100644 --- a/esp-hal-common/src/ledc/timer.rs +++ b/esp-hal-common/src/ledc/timer.rs @@ -161,7 +161,8 @@ where let mut divisor = ((src_freq as u64) << 8) / frequency as u64 / precision as u64; if divisor > LEDC_TIMER_DIV_NUM_MAX { - // APB_CLK results in divisor which too high. Try using REF_TICK as clock source. + // APB_CLK results in divisor which too high. Try using REF_TICK as clock + // source. self.use_ref_tick = true; divisor = ((1_000_000 as u64) << 8) / frequency as u64 / precision as u64; } diff --git a/esp-hal-common/src/lib.rs b/esp-hal-common/src/lib.rs index be6833dc4..1a6236e1a 100644 --- a/esp-hal-common/src/lib.rs +++ b/esp-hal-common/src/lib.rs @@ -17,6 +17,7 @@ //! [esp32s3-hal]: https://github.com/esp-rs/esp-hal/tree/main/esp32s3-hal #![no_std] +#![cfg_attr(target_arch = "xtensa", feature(asm_experimental_arch))] #[cfg(feature = "esp32")] pub use esp32_pac as pac; @@ -101,3 +102,120 @@ pub fn get_core() -> Cpu { #[cfg(feature = "single_core")] Cpu::ProCpu } + +mod critical_section_impl { + struct CriticalSection; + + critical_section::set_impl!(CriticalSection); + + #[cfg(target_arch = "xtensa")] + mod xtensa { + + unsafe impl critical_section::Impl for super::CriticalSection { + unsafe fn acquire() -> critical_section::RawRestoreState { + let tkn: critical_section::RawRestoreState; + core::arch::asm!("rsil {0}, 15", out(reg) tkn); + #[cfg(feature = "multicore")] + { + let guard = multicore::MULTICORE_LOCK.lock(); + core::mem::forget(guard); // forget it so drop doesn't run + } + tkn + } + + unsafe fn release(token: critical_section::RawRestoreState) { + if token != 0 { + #[cfg(feature = "multicore")] + { + debug_assert!(multicore::MULTICORE_LOCK.is_owned_by_current_thread()); + // safety: we logically own the mutex from acquire() + multicore::MULTICORE_LOCK.force_unlock(); + } + core::arch::asm!( + "wsr.ps {0}", + "rsync", in(reg) token) + } + } + } + } + + #[cfg(target_arch = "riscv32")] + mod riscv { + unsafe impl critical_section::Impl for super::CriticalSection { + unsafe fn acquire() -> critical_section::RawRestoreState { + let interrupts_active = riscv::register::mstatus::read().mie(); + riscv::interrupt::disable(); + + #[cfg(feature = "multicore")] + { + let guard = multicore::MULTICORE_LOCK.lock(); + core::mem::forget(guard); // forget it so drop doesn't run + } + + interrupts_active as _ + } + + unsafe fn release(token: critical_section::RawRestoreState) { + if token != 0 { + #[cfg(feature = "multicore")] + { + debug_assert!(multicore::MULTICORE_LOCK.is_owned_by_current_thread()); + // safety: we logically own the mutex from acquire() + multicore::MULTICORE_LOCK.force_unlock(); + } + riscv::interrupt::enable(); + } + } + } + } + + #[cfg(feature = "multicore")] + mod multicore { + use core::sync::atomic::{AtomicBool, Ordering}; + + use lock_api::{GetThreadId, GuardSend, RawMutex}; + + use crate::get_core; + + /// Reentrant Mutex + /// + /// Currently implemented using an atomic spin lock. + /// In the future we can optimize this raw mutex to use some hardware + /// features. + pub(crate) static MULTICORE_LOCK: lock_api::ReentrantMutex = + lock_api::ReentrantMutex::const_new(RawSpinlock::INIT, RawThreadId::INIT, ()); + + pub(crate) struct RawThreadId; + + unsafe impl lock_api::GetThreadId for RawThreadId { + const INIT: Self = RawThreadId; + + fn nonzero_thread_id(&self) -> core::num::NonZeroUsize { + core::num::NonZeroUsize::new((get_core() as usize) + 1).unwrap() + } + } + + pub(crate) struct RawSpinlock(AtomicBool); + + unsafe impl lock_api::RawMutex for RawSpinlock { + const INIT: RawSpinlock = RawSpinlock(AtomicBool::new(false)); + + // A spinlock guard can be sent to another thread and unlocked there + type GuardMarker = GuardSend; + + fn lock(&self) { + while !self.try_lock() {} + } + + fn try_lock(&self) -> bool { + self.0 + .compare_exchange(false, true, Ordering::Acquire, Ordering::Relaxed) + .is_ok() + } + + unsafe fn unlock(&self) { + self.0.store(false, Ordering::Release); + } + } + } +} diff --git a/esp-hal-common/src/rtc/esp32.rs b/esp-hal-common/src/rtc/esp32.rs index 4fece1c8b..9459ec636 100644 --- a/esp-hal-common/src/rtc/esp32.rs +++ b/esp-hal-common/src/rtc/esp32.rs @@ -1,6 +1,8 @@ -use crate::{clock::XtalClock, pac::RTC_CNTL}; - -use crate::rtc_cntl::{RtcCalSel, RtcClock, RtcFastClock, RtcSlowClock}; +use crate::{ + clock::XtalClock, + pac::RTC_CNTL, + rtc_cntl::{RtcCalSel, RtcClock, RtcFastClock, RtcSlowClock}, +}; pub(crate) fn init() {} diff --git a/esp-hal-common/src/rtc/esp32c3.rs b/esp-hal-common/src/rtc/esp32c3.rs index 9e682555a..9376313a8 100644 --- a/esp-hal-common/src/rtc/esp32c3.rs +++ b/esp-hal-common/src/rtc/esp32c3.rs @@ -1,14 +1,13 @@ use paste::paste; use crate::{ - clock::XtalClock, pac::APB_CTRL, pac::EXTMEM, pac::RTC_CNTL, pac::SPI0, pac::SPI1, pac::SYSTEM, + clock::XtalClock, + pac::{APB_CTRL, EXTMEM, RTC_CNTL, SPI0, SPI1, SYSTEM}, + regi2c_write_mask, + rom::regi2c_ctrl_write_reg_mask, + rtc_cntl::{RtcCalSel, RtcClock, RtcFastClock, RtcSlowClock}, }; -use crate::rtc_cntl::{RtcCalSel, RtcClock, RtcFastClock, RtcSlowClock}; - -use crate::regi2c_write_mask; -use crate::rom::regi2c_ctrl_write_reg_mask; - const I2C_DIG_REG: u32 = 0x6d; const I2C_DIG_REG_HOSTID: u32 = 0; diff --git a/esp-hal-common/src/rtc/esp32s2.rs b/esp-hal-common/src/rtc/esp32s2.rs index 4fece1c8b..9459ec636 100644 --- a/esp-hal-common/src/rtc/esp32s2.rs +++ b/esp-hal-common/src/rtc/esp32s2.rs @@ -1,6 +1,8 @@ -use crate::{clock::XtalClock, pac::RTC_CNTL}; - -use crate::rtc_cntl::{RtcCalSel, RtcClock, RtcFastClock, RtcSlowClock}; +use crate::{ + clock::XtalClock, + pac::RTC_CNTL, + rtc_cntl::{RtcCalSel, RtcClock, RtcFastClock, RtcSlowClock}, +}; pub(crate) fn init() {} diff --git a/esp-hal-common/src/rtc/esp32s3.rs b/esp-hal-common/src/rtc/esp32s3.rs index 4fece1c8b..9459ec636 100644 --- a/esp-hal-common/src/rtc/esp32s3.rs +++ b/esp-hal-common/src/rtc/esp32s3.rs @@ -1,6 +1,8 @@ -use crate::{clock::XtalClock, pac::RTC_CNTL}; - -use crate::rtc_cntl::{RtcCalSel, RtcClock, RtcFastClock, RtcSlowClock}; +use crate::{ + clock::XtalClock, + pac::RTC_CNTL, + rtc_cntl::{RtcCalSel, RtcClock, RtcFastClock, RtcSlowClock}, +}; pub(crate) fn init() {} diff --git a/esp-hal-common/src/rtc_cntl.rs b/esp-hal-common/src/rtc_cntl.rs index c35ad0f90..4ff36d06e 100644 --- a/esp-hal-common/src/rtc_cntl.rs +++ b/esp-hal-common/src/rtc_cntl.rs @@ -1,13 +1,13 @@ -use fugit::{HertzU32, MicrosDurationU64}; - use embedded_hal::watchdog::{Watchdog, WatchdogDisable, WatchdogEnable}; - -use crate::{clock::Clock, clock::XtalClock, pac::RTC_CNTL, pac::TIMG0}; +use fugit::{HertzU32, MicrosDurationU64}; #[cfg(not(feature = "esp32"))] use crate::efuse::Efuse; - -use crate::rom::esp_rom_delay_us; +use crate::{ + clock::{Clock, XtalClock}, + pac::{RTC_CNTL, TIMG0}, + rom::esp_rom_delay_us, +}; #[cfg_attr(feature = "esp32", path = "rtc/esp32.rs")] #[cfg_attr(feature = "esp32s2", path = "rtc/esp32s2.rs")] @@ -22,7 +22,7 @@ pub(crate) enum RtcFastClock { /// Main XTAL, divided by 4 RtcFastClockXtalD4 = 0, /// Internal fast RC oscillator - RtcFastClock8m = 1, + RtcFastClock8m = 1, } impl Clock for RtcFastClock { @@ -42,11 +42,11 @@ impl Clock for RtcFastClock { /// RTC SLOW_CLK frequency values pub(crate) enum RtcSlowClock { /// Internal slow RC oscillator - RtcSlowClockRtc = 0, + RtcSlowClockRtc = 0, /// External 32 KHz XTAL RtcSlowClock32kXtal = 1, /// Internal fast RC oscillator, divided by 256 - RtcSlowClock8mD256 = 2, + RtcSlowClock8mD256 = 2, } impl Clock for RtcSlowClock { @@ -72,11 +72,11 @@ impl Clock for RtcSlowClock { /// Clock source to be calibrated using rtc_clk_cal function pub(crate) enum RtcCalSel { /// Currently selected RTC SLOW_CLK - RtcCalRtcMux = 0, + RtcCalRtcMux = 0, /// Internal 8 MHz RC oscillator, divided by 256 - RtcCal8mD256 = 1, + RtcCal8mD256 = 1, /// External 32 KHz XTAL - RtcCal32kXtal = 2, + RtcCal32kXtal = 2, #[cfg(not(feature = "esp32"))] /// Internal 150 KHz RC oscillator RtcCalInternalOsc = 3, @@ -118,12 +118,13 @@ impl RtcClock { /// Output from 8 MHz internal oscillator is passed into a configurable /// divider, which by default divides the input clock frequency by 256. /// Output of the divider may be used as RTC_SLOW_CLK source. - /// Output of the divider is referred to in register descriptions and code as - /// 8md256 or simply d256. Divider values other than 256 may be configured, but - /// this facility is not currently needed, so is not exposed in the code. + /// Output of the divider is referred to in register descriptions and code + /// as 8md256 or simply d256. Divider values other than 256 may be + /// configured, but this facility is not currently needed, so is not + /// exposed in the code. /// - /// When 8MHz/256 divided output is not needed, the divider should be disabled - /// to reduce power consumption. + /// When 8MHz/256 divided output is not needed, the divider should be + /// disabled to reduce power consumption. fn enable_8m(clk_8m_en: bool, d256_en: bool) { let rtc_cntl = unsafe { &*RTC_CNTL::ptr() }; @@ -150,8 +151,8 @@ impl RtcClock { } /// Get main XTAL frequency - /// This is the value stored in RTC register RTC_XTAL_FREQ_REG by the bootloader, as passed to - /// rtc_clk_init function. + /// This is the value stored in RTC register RTC_XTAL_FREQ_REG by the + /// bootloader, as passed to rtc_clk_init function. fn get_xtal_freq() -> XtalClock { let rtc_cntl = unsafe { &*RTC_CNTL::ptr() }; let xtal_freq_reg = rtc_cntl.store4.read().bits(); @@ -235,13 +236,13 @@ impl RtcClock { }; } - /// Calibration of RTC_SLOW_CLK is performed using a special feature of TIMG0. - /// This feature counts the number of XTAL clock cycles within a given number of - /// RTC_SLOW_CLK cycles. + /// Calibration of RTC_SLOW_CLK is performed using a special feature of + /// TIMG0. This feature counts the number of XTAL clock cycles within a + /// given number of RTC_SLOW_CLK cycles. fn calibrate_internal(cal_clk: RtcCalSel, slowclk_cycles: u32) -> u32 { // Except for ESP32, choosing RTC_CAL_RTC_MUX results in calibration of - // the 150k RTC clock (90k on ESP32-S2) regardless of the currently selected SLOW_CLK. - // On the ESP32, it uses the currently selected SLOW_CLK. + // the 150k RTC clock (90k on ESP32-S2) regardless of the currently selected + // SLOW_CLK. On the ESP32, it uses the currently selected SLOW_CLK. // The following code emulates ESP32 behavior for the other chips: #[cfg(not(feature = "esp32"))] let cal_clk = match cal_clk { @@ -281,7 +282,8 @@ impl RtcClock { .bit_is_set() { // Set a small timeout threshold to accelerate the generation of timeout. - // The internal circuit will be reset when the timeout occurs and will not affect the next calibration. + // The internal circuit will be reset when the timeout occurs and will not + // affect the next calibration. timg0 .rtccalicfg2 .modify(|_, w| unsafe { w.rtc_cali_timeout_thres().bits(1) }); @@ -391,10 +393,11 @@ impl RtcClock { /// Measure RTC slow clock's period, based on main XTAL frequency /// - /// This function will time out and return 0 if the time for the given number - /// of cycles to be counted exceeds the expected time twice. This may happen if - /// 32k XTAL is being calibrated, but the oscillator has not started up (due to - /// incorrect loading capacitance, board design issue, or lack of 32 XTAL on board). + /// This function will time out and return 0 if the time for the given + /// number of cycles to be counted exceeds the expected time twice. This + /// may happen if 32k XTAL is being calibrated, but the oscillator has + /// not started up (due to incorrect loading capacitance, board design + /// issue, or lack of 32 XTAL on board). fn calibrate(cal_clk: RtcCalSel, slowclk_cycles: u32) -> u32 { let xtal_freq = RtcClock::get_xtal_freq(); let xtal_cycles = RtcClock::calibrate_internal(cal_clk, slowclk_cycles) as u64; @@ -448,11 +451,11 @@ impl RtcClock { #[allow(unused)] #[derive(Debug, Clone, Copy)] enum RwdtStageAction { - RwdtStageActionOff = 0, - RwdtStageActionInterrupt = 1, - RwdtStageActionResetCpu = 2, + RwdtStageActionOff = 0, + RwdtStageActionInterrupt = 1, + RwdtStageActionResetCpu = 2, RwdtStageActionResetSystem = 3, - RwdtStageActionResetRtc = 4, + RwdtStageActionResetRtc = 4, } /// RTC Watchdog Timer @@ -580,7 +583,9 @@ impl WatchdogDisable for Rwdt { self.set_write_protection(false); - rtc_cntl.wdtconfig0.modify(|_, w| w.wdt_en().clear_bit().wdt_flashboot_mod_en().clear_bit()); + rtc_cntl + .wdtconfig0 + .modify(|_, w| w.wdt_en().clear_bit().wdt_flashboot_mod_en().clear_bit()); self.set_write_protection(true); } diff --git a/esp-hal-common/src/spi.rs b/esp-hal-common/src/spi.rs index 6a7cb8638..f2c58d780 100644 --- a/esp-hal-common/src/spi.rs +++ b/esp-hal-common/src/spi.rs @@ -22,15 +22,18 @@ //! ); //! ``` +use core::convert::Infallible; + +use fugit::HertzU32; + use crate::{ clock::Clocks, pac::spi2::RegisterBlock, system::PeripheralClockControl, types::{InputSignal, OutputSignal}, - InputPin, OutputPin, + InputPin, + OutputPin, }; -use core::convert::Infallible; -use fugit::HertzU32; /// The size of the FIFO buffer for SPI #[cfg(not(feature = "esp32s2"))] @@ -209,10 +212,12 @@ pub use ehal1::*; #[cfg(feature = "eh1")] mod ehal1 { - use super::*; - use embedded_hal_1::spi::blocking::{SpiBus, SpiBusFlush, SpiBusRead, SpiBusWrite}; - use embedded_hal_1::spi::nb::FullDuplex; + use embedded_hal_1::spi::{ + blocking::{SpiBus, SpiBusFlush, SpiBusRead, SpiBusWrite}, + nb::FullDuplex, + }; + use super::*; impl embedded_hal_1::spi::ErrorType for Spi { type Error = Infallible; @@ -257,9 +262,10 @@ mod ehal1 { { /// Write out data from `write`, read response into `read`. /// - /// `read` and `write` are allowed to have different lengths. If `write` is longer, all - /// other bytes received are discarded. If `read` is longer, [`EMPTY_WRITE_PAD`] is written - /// out as necessary until enough bytes have been read. Reading and writing happens + /// `read` and `write` are allowed to have different lengths. If `write` + /// is longer, all other bytes received are discarded. If `read` + /// is longer, [`EMPTY_WRITE_PAD`] is written out as necessary + /// until enough bytes have been read. Reading and writing happens /// simultaneously. fn transfer(&mut self, read: &mut [u8], write: &[u8]) -> Result<(), Self::Error> { // Optimizations @@ -296,7 +302,8 @@ mod ehal1 { SpiBusFlush::flush(self)?; if read_inc > 0 { - self.spi.read_bytes_from_fifo(&mut read[read_from..read_to])?; + self.spi + .read_bytes_from_fifo(&mut read[read_from..read_to])?; } write_from = write_to; @@ -307,8 +314,9 @@ mod ehal1 { /// Transfer data in place. /// - /// Writes data from `words` out on the bus and stores the reply into `words`. A convenient - /// wrapper around [`write`](SpiBusWrite::write), [`flush`](SpiBusFlush::flush) and + /// Writes data from `words` out on the bus and stores the reply into + /// `words`. A convenient wrapper around + /// [`write`](SpiBusWrite::write), [`flush`](SpiBusFlush::flush) and /// [`read`](SpiBusRead::read). fn transfer_in_place(&mut self, words: &mut [u8]) -> Result<(), Self::Error> { // Since we have the traits so neatly implemented above, use them! @@ -548,9 +556,10 @@ pub trait Instance { /// Write bytes to SPI. /// - /// Copies the content of `words` in chunks of 64 bytes into the SPI transmission FIFO. If - /// `words` is longer than 64 bytes, multiple sequential transfers are performed. This function - /// will return before all bytes of the last chunk to transmit have been sent to the wire. If + /// Copies the content of `words` in chunks of 64 bytes into the SPI + /// transmission FIFO. If `words` is longer than 64 bytes, multiple + /// sequential transfers are performed. This function will return before + /// all bytes of the last chunk to transmit have been sent to the wire. If /// you must ensure that the whole messages was written correctly, use /// [`flush`]. // FIXME: See below. @@ -558,14 +567,15 @@ pub trait Instance { let reg_block = self.register_block(); let num_chunks = words.len() / FIFO_SIZE; - // The fifo has a limited fixed size, so the data must be chunked and then transmitted + // The fifo has a limited fixed size, so the data must be chunked and then + // transmitted for (i, chunk) in words.chunks(FIFO_SIZE).enumerate() { self.configure_datalen(chunk.len() as u32 * 8); let fifo_ptr = reg_block.w0.as_ptr(); unsafe { - // It seems that `copy_nonoverlapping` is significantly faster than regular `copy`, - // by about 20%... ? + // It seems that `copy_nonoverlapping` is significantly faster than regular + // `copy`, by about 20%... ? core::ptr::copy_nonoverlapping::( chunk.as_ptr() as *const u32, fifo_ptr as *mut u32, @@ -593,9 +603,9 @@ pub trait Instance { /// Read bytes from SPI. /// - /// Sends out a stuffing byte for every byte to read. This function doesn't perform flushing. - /// If you want to read the response to something you have written before, consider using - /// [`transfer`] instead. + /// Sends out a stuffing byte for every byte to read. This function doesn't + /// perform flushing. If you want to read the response to something you + /// have written before, consider using [`transfer`] instead. fn read_bytes(&mut self, words: &mut [u8]) -> Result<(), Infallible> { let empty_array = [EMPTY_WRITE_PAD; FIFO_SIZE]; @@ -607,15 +617,15 @@ pub trait Instance { Ok(()) } - /// Read received bytes from SPI FIFO. /// - /// Copies the contents of the SPI receive FIFO into `words`. This function doesn't perform - /// flushing. If you want to read the response to something you have written before, consider - /// using [`transfer`] instead. - // FIXME: Using something like `core::slice::from_raw_parts` and `copy_from_slice` on the - // receive registers works only for the esp32 and esp32c3 varaints. The reason for this is - // unknown. + /// Copies the contents of the SPI receive FIFO into `words`. This function + /// doesn't perform flushing. If you want to read the response to + /// something you have written before, consider using [`transfer`] + /// instead. + // FIXME: Using something like `core::slice::from_raw_parts` and + // `copy_from_slice` on the receive registers works only for the esp32 and + // esp32c3 varaints. The reason for this is unknown. fn read_bytes_from_fifo(&mut self, words: &mut [u8]) -> Result<(), Infallible> { let reg_block = self.register_block(); diff --git a/esp32-hal/Cargo.toml b/esp32-hal/Cargo.toml index c7cfaf7d5..182119f4f 100644 --- a/esp32-hal/Cargo.toml +++ b/esp32-hal/Cargo.toml @@ -37,10 +37,11 @@ features = ["esp32"] [dev-dependencies] embedded-graphics = "0.7" -panic-halt = "0.2" ssd1306 = "0.7" smart-leds = "0.3" esp-println = { version = "0.2.0", features = ["esp32"] } +esp-backtrace = { version = "0.2", features = ["esp32", "panic-handler", "exception-handler", "print-uart"] } +critical-section = "1" [features] default = ["rt", "vectored"] diff --git a/esp32-hal/examples/adc.rs b/esp32-hal/examples/adc.rs index 9a4ffb7da..d04c3a0e0 100644 --- a/esp32-hal/examples/adc.rs +++ b/esp32-hal/examples/adc.rs @@ -15,8 +15,8 @@ use esp32_hal::{ Delay, Rtc, }; +use esp_backtrace as _; use esp_println::println; -use panic_halt as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32-hal/examples/advanced_serial.rs b/esp32-hal/examples/advanced_serial.rs index 4a870c752..199b0dc61 100644 --- a/esp32-hal/examples/advanced_serial.rs +++ b/esp32-hal/examples/advanced_serial.rs @@ -20,9 +20,9 @@ use esp32_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use esp_println::println; use nb::block; -use panic_halt as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32-hal/examples/blinky.rs b/esp32-hal/examples/blinky.rs index 526a7a220..fdec5ff30 100644 --- a/esp32-hal/examples/blinky.rs +++ b/esp32-hal/examples/blinky.rs @@ -14,7 +14,7 @@ use esp32_hal::{ Delay, Rtc, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32-hal/examples/clock_monitor.rs b/esp32-hal/examples/clock_monitor.rs index 15a51dcd7..35ae95270 100644 --- a/esp32-hal/examples/clock_monitor.rs +++ b/esp32-hal/examples/clock_monitor.rs @@ -7,6 +7,7 @@ use core::cell::RefCell; +use critical_section::Mutex; use esp32_hal::{ clock::ClockControl, interrupt, @@ -14,12 +15,10 @@ use esp32_hal::{ prelude::*, Rtc, }; -use panic_halt as _; -use xtensa_lx::mutex::{CriticalSectionMutex, Mutex}; +use esp_backtrace as _; use xtensa_lx_rt::entry; -static mut RTC: CriticalSectionMutex>> = - CriticalSectionMutex::new(RefCell::new(None)); +static RTC: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -43,27 +42,23 @@ fn main() -> ! { interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap(); - unsafe { - (&RTC).lock(|data| (*data).replace(Some(rtc))); - } + critical_section::with(|cs| RTC.borrow_ref_mut(cs).replace(rtc)); loop {} } #[interrupt] fn RTC_CORE() { - unsafe { - (&RTC).lock(|data| { - let mut rtc = data.borrow_mut(); - let rtc = rtc.as_mut().unwrap(); + critical_section::with(|cs| { + let mut rtc = RTC.borrow_ref_mut(cs); + let rtc = rtc.as_mut().unwrap(); - esp_println::println!( - "{: <10} XTAL frequency: {} MHz", - "[Monitor]", - rtc.estimate_xtal_frequency() - ); + esp_println::println!( + "{: <10} XTAL frequency: {} MHz", + "[Monitor]", + rtc.estimate_xtal_frequency() + ); - rtc.rwdt.clear_interrupt(); - }); - } + rtc.rwdt.clear_interrupt(); + }); } diff --git a/esp32-hal/examples/dac.rs b/esp32-hal/examples/dac.rs index e11ad00b1..5eaec3be8 100644 --- a/esp32-hal/examples/dac.rs +++ b/esp32-hal/examples/dac.rs @@ -15,7 +15,7 @@ use esp32_hal::{ Delay, Rtc, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32-hal/examples/gpio_interrupt.rs b/esp32-hal/examples/gpio_interrupt.rs index 3977d32e7..8076d879c 100644 --- a/esp32-hal/examples/gpio_interrupt.rs +++ b/esp32-hal/examples/gpio_interrupt.rs @@ -6,8 +6,9 @@ #![no_std] #![no_main] -use core::cell::RefCell; +use core::{borrow::BorrowMut, cell::RefCell}; +use critical_section::Mutex; use esp32_hal::{ clock::ClockControl, gpio::{Gpio0, IO}, @@ -20,12 +21,10 @@ use esp32_hal::{ Delay, Rtc, }; -use panic_halt as _; -use xtensa_lx::mutex::{Mutex, SpinLockMutex}; +use esp_backtrace as _; use xtensa_lx_rt::entry; -static mut BUTTON: SpinLockMutex>>>> = - SpinLockMutex::new(RefCell::new(None)); +static BUTTON: Mutex>>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -48,9 +47,7 @@ fn main() -> ! { let mut button = io.pins.gpio0.into_pull_down_input(); button.listen(Event::FallingEdge); - unsafe { - (&BUTTON).lock(|data| (*data).replace(Some(button))); - } + critical_section::with(|cs| BUTTON.borrow_ref_mut(cs).replace(button)); interrupt::enable(pac::Interrupt::GPIO, interrupt::Priority::Priority2).unwrap(); @@ -68,17 +65,18 @@ fn main() -> ! { #[ram] #[interrupt] -fn GPIO() { - unsafe { - esp_println::println!( - "GPIO Interrupt with priority {}", - xtensa_lx::interrupt::get_level() - ); +unsafe fn GPIO() { + esp_println::println!( + "GPIO Interrupt with priority {}", + xtensa_lx::interrupt::get_level() + ); - (&BUTTON).lock(|data| { - let mut button = data.borrow_mut(); - let button = button.as_mut().unwrap(); - button.clear_interrupt(); - }); - } + critical_section::with(|cs| { + BUTTON + .borrow_ref_mut(cs) + .borrow_mut() + .as_mut() + .unwrap() + .clear_interrupt(); + }); } diff --git a/esp32-hal/examples/hello_rgb.rs b/esp32-hal/examples/hello_rgb.rs index 01573fa43..3d3a9d82d 100644 --- a/esp32-hal/examples/hello_rgb.rs +++ b/esp32-hal/examples/hello_rgb.rs @@ -25,7 +25,7 @@ use esp32_hal::{ IO, }; #[allow(unused_imports)] -use panic_halt as _; +use esp_backtrace as _; use smart_leds::{ brightness, gamma, diff --git a/esp32-hal/examples/hello_world.rs b/esp32-hal/examples/hello_world.rs index a349fbe20..6925b2b00 100644 --- a/esp32-hal/examples/hello_world.rs +++ b/esp32-hal/examples/hello_world.rs @@ -14,8 +14,8 @@ use esp32_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32-hal/examples/i2c_display.rs b/esp32-hal/examples/i2c_display.rs index 74f6f79d4..2e05e9fb7 100644 --- a/esp32-hal/examples/i2c_display.rs +++ b/esp32-hal/examples/i2c_display.rs @@ -31,8 +31,8 @@ use esp32_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use ssd1306::{prelude::*, I2CDisplayInterface, Ssd1306}; use xtensa_lx_rt::entry; diff --git a/esp32-hal/examples/ledc.rs b/esp32-hal/examples/ledc.rs index d3bfe7a70..38e35736c 100644 --- a/esp32-hal/examples/ledc.rs +++ b/esp32-hal/examples/ledc.rs @@ -23,7 +23,7 @@ use esp32_hal::{ Rtc, Serial, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32-hal/examples/multicore.rs b/esp32-hal/examples/multicore.rs index 184e9f2d8..93aaedef9 100644 --- a/esp32-hal/examples/multicore.rs +++ b/esp32-hal/examples/multicore.rs @@ -5,8 +5,9 @@ #![no_std] #![no_main] -use core::sync::atomic::{AtomicI32, Ordering}; +use core::cell::RefCell; +use critical_section::Mutex; use esp32_hal::{ clock::ClockControl, pac::{Peripherals, TIMG1}, @@ -15,10 +16,9 @@ use esp32_hal::{ CpuControl, Rtc, }; +use esp_backtrace as _; use esp_println::println; use nb::block; -use panic_halt as _; -use xtensa_lx::mutex::Mutex; use xtensa_lx_rt::entry; #[entry] @@ -45,7 +45,7 @@ fn main() -> ! { timer0.start(1u64.secs()); timer1.start(500u64.millis()); - let counter = xtensa_lx::mutex::SpinLockMutex::new(AtomicI32::new(0)); + let counter = Mutex::new(RefCell::new(0)); let mut cpu_control = CpuControl::new(system.cpu_control); let mut cpu1_fnctn = || { @@ -56,24 +56,19 @@ fn main() -> ! { loop { block!(timer0.wait()).unwrap(); - let count = (&counter).lock(|counter| counter.load(Ordering::Relaxed)); + let count = critical_section::with(|cs| *counter.borrow_ref(cs)); println!("Hello World - Core 0! Counter is {}", count); } } fn cpu1_task( timer: &mut Timer>, - counter: &xtensa_lx::mutex::SpinLockMutex, + counter: &critical_section::Mutex>, ) -> ! { println!("Hello World - Core 1!"); loop { block!(timer.wait()).unwrap(); - (&*counter).lock(|counter| { - counter.store( - counter.load(Ordering::Relaxed).wrapping_add(1), - Ordering::Relaxed, - ); - }); + critical_section::with(|cs| counter.borrow_ref_mut(cs).wrapping_add(1)); } } diff --git a/esp32-hal/examples/pulse_control.rs b/esp32-hal/examples/pulse_control.rs index 9586b94c0..569ed839f 100644 --- a/esp32-hal/examples/pulse_control.rs +++ b/esp32-hal/examples/pulse_control.rs @@ -15,7 +15,7 @@ use esp32_hal::{ PulseControl, Rtc, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32-hal/examples/ram.rs b/esp32-hal/examples/ram.rs index 1a89c8414..b2b3e9c05 100644 --- a/esp32-hal/examples/ram.rs +++ b/esp32-hal/examples/ram.rs @@ -18,8 +18,8 @@ use esp32_hal::{ timer::TimerGroup, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use xtensa_lx_rt::entry; #[ram(rtc_fast)] diff --git a/esp32-hal/examples/read_efuse.rs b/esp32-hal/examples/read_efuse.rs index 4e8237d87..7eed5c329 100644 --- a/esp32-hal/examples/read_efuse.rs +++ b/esp32-hal/examples/read_efuse.rs @@ -15,7 +15,7 @@ use esp32_hal::{ Rtc, Serial, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32-hal/examples/rtc_watchdog.rs b/esp32-hal/examples/rtc_watchdog.rs index 45041da75..81ef52f28 100644 --- a/esp32-hal/examples/rtc_watchdog.rs +++ b/esp32-hal/examples/rtc_watchdog.rs @@ -8,6 +8,7 @@ use core::cell::RefCell; +use critical_section::Mutex; use esp32_hal::{ clock::ClockControl, interrupt, @@ -16,12 +17,10 @@ use esp32_hal::{ Rtc, Rwdt, }; -use panic_halt as _; -use xtensa_lx::mutex::{CriticalSectionMutex, Mutex}; +use esp_backtrace as _; use xtensa_lx_rt::entry; -static mut RWDT: CriticalSectionMutex>> = - CriticalSectionMutex::new(RefCell::new(None)); +static RWDT: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -37,30 +36,23 @@ fn main() -> ! { rtc.rwdt.start(2000u64.millis()); rtc.rwdt.listen(); - interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap(); + critical_section::with(|cs| RWDT.borrow_ref_mut(cs).replace(rtc.rwdt)); - unsafe { - (&RWDT).lock(|data| (*data).replace(Some(rtc.rwdt))); - } + interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap(); loop {} } #[interrupt] fn RTC_CORE() { - unsafe { - (&RWDT).lock(|data| { - esp_println::println!("RWDT Interrupt"); + critical_section::with(|cs| { + let mut rwdt = RWDT.borrow_ref_mut(cs); + let rwdt = rwdt.as_mut().unwrap(); + rwdt.clear_interrupt(); - let mut rwdt = data.borrow_mut(); - let rwdt = rwdt.as_mut().unwrap(); + esp_println::println!("Restarting in 5 seconds..."); - rwdt.clear_interrupt(); - - esp_println::println!("Restarting in 5 seconds..."); - - rwdt.start(5000u64.millis()); - rwdt.unlisten(); - }); - } + rwdt.start(5000u64.millis()); + rwdt.unlisten(); + }); } diff --git a/esp32-hal/examples/serial_interrupts.rs b/esp32-hal/examples/serial_interrupts.rs index 474c3bb1c..c8c5b9a3a 100644 --- a/esp32-hal/examples/serial_interrupts.rs +++ b/esp32-hal/examples/serial_interrupts.rs @@ -7,6 +7,7 @@ use core::{cell::RefCell, fmt::Write}; +use critical_section::Mutex; use esp32_hal::{ clock::ClockControl, interrupt, @@ -17,13 +18,11 @@ use esp32_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; -use xtensa_lx::mutex::{Mutex, SpinLockMutex}; use xtensa_lx_rt::entry; -static mut SERIAL: SpinLockMutex>>> = - SpinLockMutex::new(RefCell::new(None)); +static SERIAL: Mutex>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -56,18 +55,14 @@ fn main() -> ! { timer0.start(1u64.secs()); - unsafe { - (&SERIAL).lock(|data| (*data).replace(Some(serial0))); - } + critical_section::with(|cs| SERIAL.borrow_ref_mut(cs).replace(serial0)); loop { - unsafe { - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); - writeln!(serial, "Hello World! Send a single `#` character or send at least 30 characters and see the interrupts trigger.").ok(); - }); - } + critical_section::with(|cs| { + let mut serial = SERIAL.borrow_ref_mut(cs); + let serial = serial.as_mut().unwrap(); + writeln!(serial, "Hello World! Send a single `#` character or send at least 30 characters and see the interrupts trigger.").ok(); + }); block!(timer0.wait()).unwrap(); } @@ -75,27 +70,25 @@ fn main() -> ! { #[interrupt] fn UART0() { - unsafe { - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); + critical_section::with(|cs| { + let mut serial = SERIAL.borrow_ref_mut(cs); + let serial = serial.as_mut().unwrap(); - let mut cnt = 0; - while let nb::Result::Ok(_c) = serial.read() { - cnt += 1; - } - writeln!(serial, "Read {} bytes", cnt,).ok(); + let mut cnt = 0; + while let nb::Result::Ok(_c) = serial.read() { + cnt += 1; + } + writeln!(serial, "Read {} bytes", cnt,).ok(); - writeln!( - serial, - "Interrupt AT-CMD: {} RX-FIFO-FULL: {}", - serial.at_cmd_interrupt_set(), - serial.rx_fifo_full_interrupt_set(), - ) - .ok(); + writeln!( + serial, + "Interrupt AT-CMD: {} RX-FIFO-FULL: {}", + serial.at_cmd_interrupt_set(), + serial.rx_fifo_full_interrupt_set(), + ) + .ok(); - serial.reset_at_cmd_interrupt(); - serial.reset_rx_fifo_full_interrupt(); - }); - } + serial.reset_at_cmd_interrupt(); + serial.reset_rx_fifo_full_interrupt(); + }); } diff --git a/esp32-hal/examples/spi_eh1_loopback.rs b/esp32-hal/examples/spi_eh1_loopback.rs index 5bdfa9b31..7922625ca 100644 --- a/esp32-hal/examples/spi_eh1_loopback.rs +++ b/esp32-hal/examples/spi_eh1_loopback.rs @@ -18,6 +18,7 @@ use core::fmt::Write; +use embedded_hal_1::spi::blocking::SpiBus; use esp32_hal::{ clock::ClockControl, gpio::IO, @@ -29,11 +30,9 @@ use esp32_hal::{ Rtc, Serial, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; -use embedded_hal_1::spi::blocking::SpiBus; - #[entry] fn main() -> ! { let peripherals = Peripherals::take().unwrap(); @@ -82,18 +81,17 @@ fn main() -> ! { writeln!(serial0, " SUCCESS").unwrap(); delay.delay_ms(250u32); - // --- Asymmetric transfer (Read more than we write) --- write!(serial0, "Starting asymetric transfer (read > write)...").unwrap(); let mut read: [u8; 4] = [0x00; 4]; - SpiBus::transfer(&mut spi, &mut read[0..2], &write[..]).expect("Asymmetric transfer failed"); + SpiBus::transfer(&mut spi, &mut read[0..2], &write[..]) + .expect("Asymmetric transfer failed"); assert_eq!(write[0], read[0]); assert_eq!(read[2], 0x00u8); writeln!(serial0, " SUCCESS").unwrap(); delay.delay_ms(250u32); - // --- Symmetric transfer with huge buffer --- // Only your RAM is the limit! write!(serial0, "Starting huge transfer...").unwrap(); @@ -108,8 +106,8 @@ fn main() -> ! { writeln!(serial0, " SUCCESS").unwrap(); delay.delay_ms(250u32); - - // --- Symmetric transfer with huge buffer in-place (No additional allocation needed) --- + // --- Symmetric transfer with huge buffer in-place (No additional allocation + // needed) --- write!(serial0, "Starting huge transfer (in-place)...").unwrap(); let mut write = [0x55u8; 4096]; for byte in 0..write.len() { @@ -124,4 +122,3 @@ fn main() -> ! { delay.delay_ms(250u32); } } - diff --git a/esp32-hal/examples/spi_loopback.rs b/esp32-hal/examples/spi_loopback.rs index b5457f158..04f884b6c 100644 --- a/esp32-hal/examples/spi_loopback.rs +++ b/esp32-hal/examples/spi_loopback.rs @@ -29,7 +29,7 @@ use esp32_hal::{ Rtc, Serial, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32-hal/examples/timer_interrupt.rs b/esp32-hal/examples/timer_interrupt.rs index edc6fb00a..ecf9df047 100644 --- a/esp32-hal/examples/timer_interrupt.rs +++ b/esp32-hal/examples/timer_interrupt.rs @@ -5,32 +5,25 @@ #![no_std] #![no_main] -use core::{cell::RefCell, fmt::Write}; +use core::cell::RefCell; +use critical_section::Mutex; use esp32_hal::{ clock::ClockControl, interrupt, interrupt::Priority, - pac::{self, Peripherals, TIMG0, TIMG1, UART0}, + pac::{self, Peripherals, TIMG0, TIMG1}, prelude::*, timer::{Timer, Timer0, Timer1, TimerGroup}, Rtc, - Serial, }; -use panic_halt as _; -use xtensa_lx::mutex::{Mutex, SpinLockMutex}; +use esp_backtrace as _; use xtensa_lx_rt::entry; -static mut SERIAL: SpinLockMutex>>> = - SpinLockMutex::new(RefCell::new(None)); -static mut TIMER00: SpinLockMutex>>>> = - SpinLockMutex::new(RefCell::new(None)); -static mut TIMER01: SpinLockMutex>>>> = - SpinLockMutex::new(RefCell::new(None)); -static mut TIMER10: SpinLockMutex>>>> = - SpinLockMutex::new(RefCell::new(None)); -static mut TIMER11: SpinLockMutex>>>> = - SpinLockMutex::new(RefCell::new(None)); +static TIMER00: Mutex>>>> = Mutex::new(RefCell::new(None)); +static TIMER01: Mutex>>>> = Mutex::new(RefCell::new(None)); +static TIMER10: Mutex>>>> = Mutex::new(RefCell::new(None)); +static TIMER11: Mutex>>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -49,7 +42,6 @@ fn main() -> ! { let mut timer11 = timer_group1.timer1; let mut wdt1 = timer_group1.wdt; - let serial0 = Serial::new(peripherals.UART0); let mut rtc = Rtc::new(peripherals.RTC_CNTL); // Disable MWDT and RWDT (Watchdog) flash boot protection @@ -70,97 +62,72 @@ fn main() -> ! { timer11.start(3u64.secs()); timer11.listen(); - unsafe { - (&SERIAL).lock(|data| (*data).replace(Some(serial0))); - (&TIMER00).lock(|data| (*data).replace(Some(timer00))); - (&TIMER01).lock(|data| (*data).replace(Some(timer01))); - (&TIMER10).lock(|data| (*data).replace(Some(timer10))); - (&TIMER11).lock(|data| (*data).replace(Some(timer11))); - } + critical_section::with(|cs| { + TIMER00.borrow_ref_mut(cs).replace(timer00); + TIMER01.borrow_ref_mut(cs).replace(timer01); + TIMER10.borrow_ref_mut(cs).replace(timer10); + TIMER11.borrow_ref_mut(cs).replace(timer11); + }); loop {} } #[interrupt] fn TG0_T0_LEVEL() { - unsafe { - (&TIMER00).lock(|data| { - let mut timer = data.borrow_mut(); - let timer = timer.as_mut().unwrap(); + critical_section::with(|cs| { + let mut timer = TIMER00.borrow_ref_mut(cs); + let timer = timer.as_mut().unwrap(); - if timer.is_interrupt_set() { - timer.clear_interrupt(); - timer.start(500u64.millis()); + if timer.is_interrupt_set() { + timer.clear_interrupt(); + timer.start(500u64.millis()); - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); - writeln!(serial, "Interrupt Level 2 - Timer0").ok(); - }); - } - }); - } + esp_println::println!("Interrupt Level 2 - Timer0"); + } + }); } #[interrupt] fn TG0_T1_LEVEL() { - unsafe { - (&TIMER01).lock(|data| { - let mut timer = data.borrow_mut(); - let timer = timer.as_mut().unwrap(); + critical_section::with(|cs| { + let mut timer = TIMER01.borrow_ref_mut(cs); + let timer = timer.as_mut().unwrap(); - if timer.is_interrupt_set() { - timer.clear_interrupt(); - timer.start(2500u64.millis()); + if timer.is_interrupt_set() { + timer.clear_interrupt(); + timer.start(2500u64.millis()); - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); - writeln!(serial, "Interrupt Level 2 - Timer1").ok(); - }); - } - }); - } + esp_println::println!("Interrupt Level 2 - Timer1"); + } + }); } #[interrupt] fn TG1_T0_LEVEL() { - unsafe { - (&TIMER10).lock(|data| { - let mut timer = data.borrow_mut(); - let timer = timer.as_mut().unwrap(); + critical_section::with(|cs| { + let mut timer = TIMER10.borrow_ref_mut(cs); + let timer = timer.as_mut().unwrap(); - if timer.is_interrupt_set() { - timer.clear_interrupt(); - timer.start(1u64.secs()); + if timer.is_interrupt_set() { + timer.clear_interrupt(); + timer.start(1u64.secs()); - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); - writeln!(serial, "Interrupt Level 3 - Timer0").ok(); - }); - } - }); - } + esp_println::println!("Interrupt Level 3 - Timer0"); + } + }); } #[interrupt] fn TG1_T1_LEVEL() { - unsafe { - (&TIMER11).lock(|data| { - let mut timer = data.borrow_mut(); - let timer = timer.as_mut().unwrap(); + critical_section::with(|cs| { + let mut timer = TIMER10.borrow_ref_mut(cs); + let timer = timer.as_mut().unwrap(); - if timer.is_interrupt_set() { - timer.clear_interrupt(); - timer.start(3u64.secs()); + if timer.is_interrupt_set() { + timer.clear_interrupt(); + timer.start(3u64.secs()); - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); - writeln!(serial, "Interrupt Level 3 - Timer1").ok(); - }); - } - }); - } + esp_println::println!("Interrupt Level 3 - Timer1"); + } + }); } diff --git a/esp32-hal/examples/watchdog.rs b/esp32-hal/examples/watchdog.rs index 964936a9c..6592c5504 100644 --- a/esp32-hal/examples/watchdog.rs +++ b/esp32-hal/examples/watchdog.rs @@ -15,8 +15,8 @@ use esp32_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32c3-hal/Cargo.toml b/esp32c3-hal/Cargo.toml index b46f176b3..b12931744 100644 --- a/esp32c3-hal/Cargo.toml +++ b/esp32c3-hal/Cargo.toml @@ -24,7 +24,6 @@ categories = [ ] [dependencies] -bare-metal = "1.0" embedded-hal = { version = "0.2", features = ["unproven"] } embedded-hal-1 = { package = "embedded-hal", version = "=1.0.0-alpha.8" } r0 = "1.0" @@ -37,10 +36,11 @@ features = ["esp32c3"] [dev-dependencies] embedded-graphics = "0.7" -panic-halt = "0.2" ssd1306 = "0.7" smart-leds = "0.3" esp-println = { version = "0.2.0", features = ["esp32c3"] } +esp-backtrace = { version = "0.2", features = ["esp32c3", "panic-handler", "exception-handler", "print-uart"] } +critical-section = "1" [features] default = ["rt", "vectored"] diff --git a/esp32c3-hal/examples/adc.rs b/esp32c3-hal/examples/adc.rs index 159727cf0..a01c66a73 100644 --- a/esp32c3-hal/examples/adc.rs +++ b/esp32c3-hal/examples/adc.rs @@ -17,8 +17,8 @@ use esp32c3_hal::{ Delay, Rtc, }; +use esp_backtrace as _; use esp_println::println; -use panic_halt as _; use riscv_rt::entry; #[entry] diff --git a/esp32c3-hal/examples/advanced_serial.rs b/esp32c3-hal/examples/advanced_serial.rs index 06258c768..5021d0cec 100644 --- a/esp32c3-hal/examples/advanced_serial.rs +++ b/esp32c3-hal/examples/advanced_serial.rs @@ -19,9 +19,9 @@ use esp32c3_hal::{ Serial, IO, }; +use esp_backtrace as _; use esp_println::println; use nb::block; -use panic_halt as _; use riscv_rt::entry; #[entry] diff --git a/esp32c3-hal/examples/blinky.rs b/esp32c3-hal/examples/blinky.rs index 573130546..305e867ff 100644 --- a/esp32c3-hal/examples/blinky.rs +++ b/esp32c3-hal/examples/blinky.rs @@ -15,7 +15,7 @@ use esp32c3_hal::{ Delay, Rtc, }; -use panic_halt as _; +use esp_backtrace as _; use riscv_rt::entry; #[entry] diff --git a/esp32c3-hal/examples/clock_monitor.rs b/esp32c3-hal/examples/clock_monitor.rs index e4d3dc187..925b050cc 100644 --- a/esp32c3-hal/examples/clock_monitor.rs +++ b/esp32c3-hal/examples/clock_monitor.rs @@ -1,14 +1,13 @@ -//! This demos a simple monitor for the XTAL frequency, by relying on a special feature of the -//! TIMG0 (Timer Group 0). This feature counts the number of XTAL clock cycles within a given -//! number of RTC_SLOW_CLK cycles. +//! This demos a simple monitor for the XTAL frequency, by relying on a special +//! feature of the TIMG0 (Timer Group 0). This feature counts the number of XTAL +//! clock cycles within a given number of RTC_SLOW_CLK cycles. #![no_std] #![no_main] use core::cell::RefCell; -use bare_metal::Mutex; - +use critical_section::Mutex; use esp32c3_hal::{ clock::ClockControl, interrupt, @@ -16,10 +15,10 @@ use esp32c3_hal::{ prelude::*, Rtc, }; -use panic_halt as _; +use esp_backtrace as _; use riscv_rt::entry; -static mut RTC: Mutex>> = Mutex::new(RefCell::new(None)); +static RTC: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -44,8 +43,8 @@ fn main() -> ! { interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap(); - riscv::interrupt::free(|_cs| unsafe { - RTC.get_mut().replace(Some(rtc)); + critical_section::with(|cs| { + RTC.borrow_ref_mut(cs).replace(rtc); }); unsafe { @@ -57,8 +56,8 @@ fn main() -> ! { #[interrupt] fn RTC_CORE() { - riscv::interrupt::free(|cs| unsafe { - let mut rtc = RTC.borrow(*cs).borrow_mut(); + critical_section::with(|cs| { + let mut rtc = RTC.borrow(cs).borrow_mut(); let rtc = rtc.as_mut().unwrap(); esp_println::println!( diff --git a/esp32c3-hal/examples/gpio_interrupt.rs b/esp32c3-hal/examples/gpio_interrupt.rs index b5ab6b380..a0c5c8bce 100644 --- a/esp32c3-hal/examples/gpio_interrupt.rs +++ b/esp32c3-hal/examples/gpio_interrupt.rs @@ -8,7 +8,7 @@ use core::cell::RefCell; -use bare_metal::Mutex; +use critical_section::Mutex; use esp32c3_hal::{ clock::ClockControl, gpio::{Gpio9, IO}, @@ -20,10 +20,10 @@ use esp32c3_hal::{ Delay, Rtc, }; -use panic_halt as _; +use esp_backtrace as _; use riscv_rt::entry; -static mut BUTTON: Mutex>>>> = Mutex::new(RefCell::new(None)); +static BUTTON: Mutex>>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -52,9 +52,7 @@ fn main() -> ! { let mut button = io.pins.gpio9.into_pull_down_input(); button.listen(Event::FallingEdge); - riscv::interrupt::free(|_cs| unsafe { - BUTTON.get_mut().replace(Some(button)); - }); + critical_section::with(|cs| BUTTON.borrow_ref_mut(cs).replace(button)); interrupt::enable(pac::Interrupt::GPIO, interrupt::Priority::Priority3).unwrap(); @@ -71,10 +69,12 @@ fn main() -> ! { #[interrupt] fn GPIO() { - riscv::interrupt::free(|cs| unsafe { - let mut button = BUTTON.borrow(*cs).borrow_mut(); - let button = button.as_mut().unwrap(); + critical_section::with(|cs| { esp_println::println!("GPIO interrupt"); - button.clear_interrupt(); + BUTTON + .borrow_ref_mut(cs) + .as_mut() + .unwrap() + .clear_interrupt(); }); } diff --git a/esp32c3-hal/examples/hello_rgb.rs b/esp32c3-hal/examples/hello_rgb.rs index 65ec81003..f58453000 100644 --- a/esp32c3-hal/examples/hello_rgb.rs +++ b/esp32c3-hal/examples/hello_rgb.rs @@ -24,7 +24,7 @@ use esp32c3_hal::{ IO, }; #[allow(unused_imports)] -use panic_halt; +use esp_backtrace as _; use riscv_rt::entry; use smart_leds::{ brightness, diff --git a/esp32c3-hal/examples/hello_world.rs b/esp32c3-hal/examples/hello_world.rs index ed37647ee..70f5ca5ea 100644 --- a/esp32c3-hal/examples/hello_world.rs +++ b/esp32c3-hal/examples/hello_world.rs @@ -14,8 +14,8 @@ use esp32c3_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use riscv_rt::entry; #[entry] diff --git a/esp32c3-hal/examples/i2c_display.rs b/esp32c3-hal/examples/i2c_display.rs index 6f4b8a8f3..fde888295 100644 --- a/esp32c3-hal/examples/i2c_display.rs +++ b/esp32c3-hal/examples/i2c_display.rs @@ -28,8 +28,8 @@ use esp32c3_hal::{ timer::TimerGroup, Rtc, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use riscv_rt::entry; use ssd1306::{prelude::*, I2CDisplayInterface, Ssd1306}; diff --git a/esp32c3-hal/examples/ledc.rs b/esp32c3-hal/examples/ledc.rs index eec600021..53f118d06 100644 --- a/esp32c3-hal/examples/ledc.rs +++ b/esp32c3-hal/examples/ledc.rs @@ -21,8 +21,8 @@ use esp32c3_hal::{ timer::TimerGroup, Rtc, }; +use esp_backtrace as _; use esp_println; -use panic_halt as _; use riscv_rt::entry; #[entry] diff --git a/esp32c3-hal/examples/pulse_control.rs b/esp32c3-hal/examples/pulse_control.rs index 9f3d0d282..0858372bd 100644 --- a/esp32c3-hal/examples/pulse_control.rs +++ b/esp32c3-hal/examples/pulse_control.rs @@ -16,7 +16,7 @@ use esp32c3_hal::{ PulseControl, Rtc, }; -use panic_halt as _; +use esp_backtrace as _; use riscv_rt::entry; #[entry] diff --git a/esp32c3-hal/examples/ram.rs b/esp32c3-hal/examples/ram.rs index 3e7c81ab0..b40e812cc 100644 --- a/esp32c3-hal/examples/ram.rs +++ b/esp32c3-hal/examples/ram.rs @@ -18,8 +18,8 @@ use esp32c3_hal::{ timer::TimerGroup, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use riscv_rt::entry; #[ram(rtc_fast)] diff --git a/esp32c3-hal/examples/read_efuse.rs b/esp32c3-hal/examples/read_efuse.rs index 22287f6b7..7ddc85a7f 100644 --- a/esp32c3-hal/examples/read_efuse.rs +++ b/esp32c3-hal/examples/read_efuse.rs @@ -15,7 +15,7 @@ use esp32c3_hal::{ Rtc, Serial, }; -use panic_halt as _; +use esp_backtrace as _; use riscv_rt::entry; #[entry] diff --git a/esp32c3-hal/examples/rtc_watchdog.rs b/esp32c3-hal/examples/rtc_watchdog.rs index 84746f6af..a956396ad 100644 --- a/esp32c3-hal/examples/rtc_watchdog.rs +++ b/esp32c3-hal/examples/rtc_watchdog.rs @@ -8,7 +8,7 @@ use core::cell::RefCell; -use bare_metal::Mutex; +use critical_section::Mutex; use esp32c3_hal::{ clock::ClockControl, interrupt, @@ -17,10 +17,10 @@ use esp32c3_hal::{ Rtc, Rwdt, }; -use panic_halt as _; +use esp_backtrace as _; use riscv_rt::entry; -static mut RWDT: Mutex>> = Mutex::new(RefCell::new(None)); +static RWDT: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -39,9 +39,7 @@ fn main() -> ! { interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap(); - riscv::interrupt::free(|_cs| unsafe { - RWDT.get_mut().replace(Some(rtc.rwdt)); - }); + critical_section::with(|cs| RWDT.borrow_ref_mut(cs).replace(rtc.rwdt)); unsafe { riscv::interrupt::enable(); @@ -52,10 +50,10 @@ fn main() -> ! { #[interrupt] fn RTC_CORE() { - riscv::interrupt::free(|cs| unsafe { + critical_section::with(|cs| { esp_println::println!("RWDT Interrupt"); - let mut rwdt = RWDT.borrow(*cs).borrow_mut(); + let mut rwdt = RWDT.borrow_ref_mut(cs); let rwdt = rwdt.as_mut().unwrap(); rwdt.clear_interrupt(); diff --git a/esp32c3-hal/examples/serial_interrupts.rs b/esp32c3-hal/examples/serial_interrupts.rs index b1105a74f..e785a6438 100644 --- a/esp32c3-hal/examples/serial_interrupts.rs +++ b/esp32c3-hal/examples/serial_interrupts.rs @@ -7,7 +7,7 @@ use core::{cell::RefCell, fmt::Write}; -use bare_metal::Mutex; +use critical_section::Mutex; use esp32c3_hal::{ clock::ClockControl, interrupt, @@ -19,11 +19,11 @@ use esp32c3_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use riscv_rt::entry; -static mut SERIAL: Mutex>>> = Mutex::new(RefCell::new(None)); +static SERIAL: Mutex>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -52,9 +52,7 @@ fn main() -> ! { timer0.start(1u64.secs()); - riscv::interrupt::free(|_cs| unsafe { - SERIAL.get_mut().replace(Some(serial0)); - }); + critical_section::with(|cs| SERIAL.borrow_ref_mut(cs).replace(serial0)); interrupt::enable(pac::Interrupt::UART0, interrupt::Priority::Priority1).unwrap(); interrupt::set_kind( @@ -68,11 +66,8 @@ fn main() -> ! { } loop { - riscv::interrupt::free(|cs| unsafe { - let mut serial = SERIAL.borrow(*cs).borrow_mut(); - let serial = serial.as_mut().unwrap(); - - writeln!(serial, "Hello World! Send a single `#` character or send at least 30 characters and see the interrupts trigger.").ok(); + critical_section::with(|cs| { + writeln!(SERIAL.borrow_ref_mut(cs).as_mut().unwrap(), "Hello World! Send a single `#` character or send at least 30 characters and see the interrupts trigger.").ok(); }); block!(timer0.wait()).unwrap(); @@ -81,8 +76,8 @@ fn main() -> ! { #[interrupt] fn UART0() { - riscv::interrupt::free(|cs| unsafe { - let mut serial = SERIAL.borrow(*cs).borrow_mut(); + critical_section::with(|cs| { + let mut serial = SERIAL.borrow_ref_mut(cs); let serial = serial.as_mut().unwrap(); let mut cnt = 0; diff --git a/esp32c3-hal/examples/spi_eh1_loopback.rs b/esp32c3-hal/examples/spi_eh1_loopback.rs index 154f15f9d..90de69cdb 100644 --- a/esp32c3-hal/examples/spi_eh1_loopback.rs +++ b/esp32c3-hal/examples/spi_eh1_loopback.rs @@ -18,6 +18,7 @@ use core::fmt::Write; +use embedded_hal_1::spi::blocking::SpiBus; use esp32c3_hal::{ clock::ClockControl, gpio::IO, @@ -29,11 +30,9 @@ use esp32c3_hal::{ Rtc, Serial, }; -use panic_halt as _; +use esp_backtrace as _; use riscv_rt::entry; -use embedded_hal_1::spi::blocking::SpiBus; - #[entry] fn main() -> ! { let peripherals = Peripherals::take().unwrap(); @@ -87,18 +86,17 @@ fn main() -> ! { writeln!(serial0, " SUCCESS").unwrap(); delay.delay_ms(250u32); - // --- Asymmetric transfer (Read more than we write) --- write!(serial0, "Starting asymetric transfer (read > write)...").unwrap(); let mut read: [u8; 4] = [0x00; 4]; - SpiBus::transfer(&mut spi, &mut read[0..2], &write[..]).expect("Asymmetric transfer failed"); + SpiBus::transfer(&mut spi, &mut read[0..2], &write[..]) + .expect("Asymmetric transfer failed"); assert_eq!(write[0], read[0]); assert_eq!(read[2], 0x00u8); writeln!(serial0, " SUCCESS").unwrap(); delay.delay_ms(250u32); - // --- Symmetric transfer with huge buffer --- // Only your RAM is the limit! write!(serial0, "Starting huge transfer...").unwrap(); @@ -113,8 +111,8 @@ fn main() -> ! { writeln!(serial0, " SUCCESS").unwrap(); delay.delay_ms(250u32); - - // --- Symmetric transfer with huge buffer in-place (No additional allocation needed) --- + // --- Symmetric transfer with huge buffer in-place (No additional allocation + // needed) --- write!(serial0, "Starting huge transfer (in-place)...").unwrap(); let mut write = [0x55u8; 4096]; for byte in 0..write.len() { @@ -129,4 +127,3 @@ fn main() -> ! { delay.delay_ms(250u32); } } - diff --git a/esp32c3-hal/examples/spi_loopback.rs b/esp32c3-hal/examples/spi_loopback.rs index 22e88437e..020d97c36 100644 --- a/esp32c3-hal/examples/spi_loopback.rs +++ b/esp32c3-hal/examples/spi_loopback.rs @@ -29,7 +29,7 @@ use esp32c3_hal::{ Rtc, Serial, }; -use panic_halt as _; +use esp_backtrace as _; use riscv_rt::entry; #[entry] diff --git a/esp32c3-hal/examples/systimer.rs b/esp32c3-hal/examples/systimer.rs index 9f52b8dff..a8b95e2ac 100644 --- a/esp32c3-hal/examples/systimer.rs +++ b/esp32c3-hal/examples/systimer.rs @@ -6,23 +6,24 @@ use core::cell::RefCell; -use bare_metal::Mutex; +use critical_section::Mutex; use esp32c3_hal::{ clock::ClockControl, interrupt, + interrupt::Priority, pac::{self, Peripherals}, prelude::*, systimer::{Alarm, SystemTimer, Target}, timer::TimerGroup, - Cpu, + Delay, Rtc, }; -use panic_halt as _; +use esp_backtrace as _; use riscv_rt::entry; -static mut ALARM0: Mutex>>> = Mutex::new(RefCell::new(None)); -static mut ALARM1: Mutex>>> = Mutex::new(RefCell::new(None)); -static mut ALARM2: Mutex>>> = Mutex::new(RefCell::new(None)); +static ALARM0: Mutex>>> = Mutex::new(RefCell::new(None)); +static ALARM1: Mutex>>> = Mutex::new(RefCell::new(None)); +static ALARM2: Mutex>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -30,99 +31,79 @@ fn main() -> ! { let system = peripherals.SYSTEM.split(); let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); - // Disable the watchdog timers. For the ESP32-C3, this includes the Super WDT, - // the RTC WDT, and the TIMG WDTs. - let mut rtc = Rtc::new(peripherals.RTC_CNTL); let timer_group0 = TimerGroup::new(peripherals.TIMG0, &clocks); - let mut wdt0 = timer_group0.wdt; - let timer_group1 = TimerGroup::new(peripherals.TIMG1, &clocks); - let mut wdt1 = timer_group1.wdt; + let mut wdt = timer_group0.wdt; + let mut rtc = Rtc::new(peripherals.RTC_CNTL); - rtc.swd.disable(); + // Disable MWDT and RWDT (Watchdog) flash boot protection + wdt.disable(); rtc.rwdt.disable(); - wdt0.disable(); - wdt1.disable(); let syst = SystemTimer::new(peripherals.SYSTIMER); - esp_println::println!("SYSTIMER Current value = {}", SystemTimer::now()); - let alarm0 = syst.alarm0; - alarm0.set_target(40_000_000); + alarm0.set_target(40_000_0000); alarm0.enable_interrupt(); let alarm1 = syst.alarm1; - alarm1.set_target(41_111_111); + alarm1.set_target(41_111_1110); alarm1.enable_interrupt(); let alarm2 = syst.alarm2; - alarm2.set_target(42_222_222 * 2); + alarm2.set_target(42_222_2220 * 2); alarm2.enable_interrupt(); - interrupt::enable( - pac::Interrupt::SYSTIMER_TARGET0, - interrupt::Priority::Priority1, - ) - .unwrap(); - interrupt::enable( - pac::Interrupt::SYSTIMER_TARGET1, - interrupt::Priority::Priority1, - ) - .unwrap(); - interrupt::enable( - pac::Interrupt::SYSTIMER_TARGET2, - interrupt::Priority::Priority1, - ) - .unwrap(); - - riscv::interrupt::free(|_cs| unsafe { - ALARM0.get_mut().replace(Some(alarm0)); - ALARM1.get_mut().replace(Some(alarm1)); - ALARM2.get_mut().replace(Some(alarm2)); + critical_section::with(|cs| { + ALARM0.borrow_ref_mut(cs).replace(alarm0); + ALARM1.borrow_ref_mut(cs).replace(alarm1); + ALARM2.borrow_ref_mut(cs).replace(alarm2); }); - unsafe { - riscv::interrupt::enable(); - } + interrupt::enable(pac::Interrupt::SYSTIMER_TARGET0, Priority::Priority1).unwrap(); + interrupt::enable(pac::Interrupt::SYSTIMER_TARGET1, Priority::Priority2).unwrap(); + interrupt::enable(pac::Interrupt::SYSTIMER_TARGET2, Priority::Priority2).unwrap(); - loop {} + // Initialize the Delay peripheral, and use it to toggle the LED state in a + // loop. + let mut delay = Delay::new(&clocks); + + loop { + delay.delay_ms(500u32); + } } #[interrupt] fn SYSTIMER_TARGET0() { - riscv::interrupt::free(|cs| unsafe { - esp_println::println!("Interrupt 1 = {}", SystemTimer::now()); - - let mut alarm = ALARM0.borrow(*cs).borrow_mut(); - let alarm = alarm.as_mut().unwrap(); - - interrupt::clear(Cpu::ProCpu, interrupt::CpuInterrupt::Interrupt1); - alarm.clear_interrupt(); + esp_println::println!("Interrupt lvl1 (alarm0)"); + critical_section::with(|cs| { + ALARM0 + .borrow_ref_mut(cs) + .as_mut() + .unwrap() + .clear_interrupt() }); } #[interrupt] fn SYSTIMER_TARGET1() { - riscv::interrupt::free(|cs| unsafe { - esp_println::println!("Interrupt 2 = {}", SystemTimer::now()); - - let mut alarm = ALARM1.borrow(*cs).borrow_mut(); - let alarm = alarm.as_mut().unwrap(); - - interrupt::clear(Cpu::ProCpu, interrupt::CpuInterrupt::Interrupt2); - alarm.clear_interrupt(); + esp_println::println!("Interrupt lvl2 (alarm1)"); + critical_section::with(|cs| { + ALARM1 + .borrow_ref_mut(cs) + .as_mut() + .unwrap() + .clear_interrupt() }); } #[interrupt] fn SYSTIMER_TARGET2() { - riscv::interrupt::free(|cs| unsafe { - esp_println::println!("Interrupt 3 = {}", SystemTimer::now()); - - let mut alarm = ALARM2.borrow(*cs).borrow_mut(); - let alarm = alarm.as_mut().unwrap(); - - interrupt::clear(Cpu::ProCpu, interrupt::CpuInterrupt::Interrupt3); - alarm.clear_interrupt(); + esp_println::println!("Interrupt lvl2 (alarm2)"); + critical_section::with(|cs| { + ALARM2 + .borrow_ref_mut(cs) + .as_mut() + .unwrap() + .clear_interrupt() }); } diff --git a/esp32c3-hal/examples/timer_interrupt.rs b/esp32c3-hal/examples/timer_interrupt.rs index b1cfa81ec..096eed2da 100644 --- a/esp32c3-hal/examples/timer_interrupt.rs +++ b/esp32c3-hal/examples/timer_interrupt.rs @@ -7,7 +7,7 @@ use core::cell::RefCell; -use bare_metal::Mutex; +use critical_section::Mutex; use esp32c3_hal::{ clock::ClockControl, interrupt, @@ -16,11 +16,11 @@ use esp32c3_hal::{ timer::{Timer, Timer0, TimerGroup}, Rtc, }; -use panic_halt as _; +use esp_backtrace as _; use riscv_rt::entry; -static mut TIMER0: Mutex>>>> = Mutex::new(RefCell::new(None)); -static mut TIMER1: Mutex>>>> = Mutex::new(RefCell::new(None)); +static TIMER0: Mutex>>>> = Mutex::new(RefCell::new(None)); +static TIMER1: Mutex>>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -51,9 +51,9 @@ fn main() -> ! { timer1.start(1u64.secs()); timer1.listen(); - riscv::interrupt::free(|_cs| unsafe { - TIMER0.get_mut().replace(Some(timer0)); - TIMER1.get_mut().replace(Some(timer1)); + critical_section::with(|cs| { + TIMER0.borrow_ref_mut(cs).replace(timer0); + TIMER1.borrow_ref_mut(cs).replace(timer1); }); unsafe { @@ -65,10 +65,10 @@ fn main() -> ! { #[interrupt] fn TG0_T0_LEVEL() { - riscv::interrupt::free(|cs| unsafe { + critical_section::with(|cs| { esp_println::println!("Interrupt 1"); - let mut timer0 = TIMER0.borrow(*cs).borrow_mut(); + let mut timer0 = TIMER0.borrow_ref_mut(cs); let timer0 = timer0.as_mut().unwrap(); timer0.clear_interrupt(); @@ -78,10 +78,10 @@ fn TG0_T0_LEVEL() { #[interrupt] fn TG1_T0_LEVEL() { - riscv::interrupt::free(|cs| unsafe { + critical_section::with(|cs| { esp_println::println!("Interrupt 11"); - let mut timer1 = TIMER1.borrow(*cs).borrow_mut(); + let mut timer1 = TIMER1.borrow_ref_mut(cs); let timer1 = timer1.as_mut().unwrap(); timer1.clear_interrupt(); diff --git a/esp32c3-hal/examples/usb_serial_jtag.rs b/esp32c3-hal/examples/usb_serial_jtag.rs index 91f77baa0..88cf674e3 100644 --- a/esp32c3-hal/examples/usb_serial_jtag.rs +++ b/esp32c3-hal/examples/usb_serial_jtag.rs @@ -17,7 +17,7 @@ use esp32c3_hal::{ Rtc, UsbSerialJtag, }; -use panic_halt as _; +use esp_backtrace as _; use riscv_rt::entry; #[entry] diff --git a/esp32c3-hal/examples/watchdog.rs b/esp32c3-hal/examples/watchdog.rs index c2aa552b9..99cbfb6d9 100644 --- a/esp32c3-hal/examples/watchdog.rs +++ b/esp32c3-hal/examples/watchdog.rs @@ -15,8 +15,8 @@ use esp32c3_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use riscv_rt::entry; #[entry] diff --git a/esp32s2-hal/Cargo.toml b/esp32s2-hal/Cargo.toml index 03e7cc871..93ab0d891 100644 --- a/esp32s2-hal/Cargo.toml +++ b/esp32s2-hal/Cargo.toml @@ -24,7 +24,6 @@ categories = [ ] [dependencies] -bare-metal = "1.0" embedded-hal = { version = "0.2", features = ["unproven"] } embedded-hal-1 = { package = "embedded-hal", version = "=1.0.0-alpha.8" } xtensa-lx = { version = "0.7", features = ["esp32s2"] } @@ -40,6 +39,8 @@ panic-halt = "0.2" ssd1306 = "0.7" smart-leds = "0.3" esp-println = { version = "0.2.0", features = ["esp32s2"] } +esp-backtrace = { version = "0.2", features = ["esp32s2", "panic-handler", "exception-handler", "print-uart"] } +critical-section = "1" [features] default = ["rt", "vectored"] diff --git a/esp32s2-hal/examples/adc.rs b/esp32s2-hal/examples/adc.rs index 937265dfd..f50585e73 100644 --- a/esp32s2-hal/examples/adc.rs +++ b/esp32s2-hal/examples/adc.rs @@ -15,8 +15,8 @@ use esp32s2_hal::{ Delay, Rtc, }; +use esp_backtrace as _; use esp_println::println; -use panic_halt as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s2-hal/examples/advanced_serial.rs b/esp32s2-hal/examples/advanced_serial.rs index 929a19630..29679929a 100644 --- a/esp32s2-hal/examples/advanced_serial.rs +++ b/esp32s2-hal/examples/advanced_serial.rs @@ -21,8 +21,8 @@ use esp32s2_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use esp_println::println; -use panic_halt as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s2-hal/examples/blinky.rs b/esp32s2-hal/examples/blinky.rs index 6e8f6aebb..ef67a5ce8 100644 --- a/esp32s2-hal/examples/blinky.rs +++ b/esp32s2-hal/examples/blinky.rs @@ -14,7 +14,7 @@ use esp32s2_hal::{ Delay, Rtc, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s2-hal/examples/clock_monitor.rs b/esp32s2-hal/examples/clock_monitor.rs index d03603882..a35c265c6 100644 --- a/esp32s2-hal/examples/clock_monitor.rs +++ b/esp32s2-hal/examples/clock_monitor.rs @@ -7,6 +7,7 @@ use core::cell::RefCell; +use critical_section::Mutex; use esp32s2_hal::{ clock::ClockControl, interrupt, @@ -14,12 +15,10 @@ use esp32s2_hal::{ prelude::*, Rtc, }; -use panic_halt as _; -use xtensa_lx::mutex::{CriticalSectionMutex, Mutex}; +use esp_backtrace as _; use xtensa_lx_rt::entry; -static mut RTC: CriticalSectionMutex>> = - CriticalSectionMutex::new(RefCell::new(None)); +static RTC: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -43,27 +42,23 @@ fn main() -> ! { interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap(); - unsafe { - (&RTC).lock(|data| (*data).replace(Some(rtc))); - } + critical_section::with(|cs| RTC.borrow_ref_mut(cs).replace(rtc)); loop {} } #[interrupt] fn RTC_CORE() { - unsafe { - (&RTC).lock(|data| { - let mut rtc = data.borrow_mut(); - let rtc = rtc.as_mut().unwrap(); + critical_section::with(|cs| { + let mut rtc = RTC.borrow_ref_mut(cs); + let rtc = rtc.as_mut().unwrap(); - esp_println::println!( - "{: <10} XTAL frequency: {} MHz", - "[Monitor]", - rtc.estimate_xtal_frequency() - ); + esp_println::println!( + "{: <10} XTAL frequency: {} MHz", + "[Monitor]", + rtc.estimate_xtal_frequency() + ); - rtc.rwdt.clear_interrupt(); - }); - } + rtc.rwdt.clear_interrupt(); + }); } diff --git a/esp32s2-hal/examples/dac.rs b/esp32s2-hal/examples/dac.rs index 4e2ea09e0..a6faf5a56 100644 --- a/esp32s2-hal/examples/dac.rs +++ b/esp32s2-hal/examples/dac.rs @@ -15,7 +15,7 @@ use esp32s2_hal::{ Delay, Rtc, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s2-hal/examples/gpio_interrupt.rs b/esp32s2-hal/examples/gpio_interrupt.rs index 4b3a65831..f527bbbeb 100644 --- a/esp32s2-hal/examples/gpio_interrupt.rs +++ b/esp32s2-hal/examples/gpio_interrupt.rs @@ -8,6 +8,7 @@ use core::cell::RefCell; +use critical_section::Mutex; use esp32s2_hal::{ clock::ClockControl, gpio::{Gpio0, IO}, @@ -20,12 +21,10 @@ use esp32s2_hal::{ Delay, Rtc, }; -use panic_halt as _; -use xtensa_lx::mutex::{CriticalSectionMutex, Mutex}; +use esp_backtrace as _; use xtensa_lx_rt::entry; -static mut BUTTON: CriticalSectionMutex>>>> = - CriticalSectionMutex::new(RefCell::new(None)); +static BUTTON: Mutex>>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -48,9 +47,7 @@ fn main() -> ! { let mut button = io.pins.gpio0.into_pull_down_input(); button.listen(Event::FallingEdge); - unsafe { - (&BUTTON).lock(|data| (*data).replace(Some(button))); - } + critical_section::with(|cs| BUTTON.borrow_ref_mut(cs).replace(button)); interrupt::enable(pac::Interrupt::GPIO, interrupt::Priority::Priority2).unwrap(); @@ -69,16 +66,15 @@ fn main() -> ! { #[ram] #[interrupt] fn GPIO() { - unsafe { - esp_println::println!( - "GPIO Interrupt with priority {}", - xtensa_lx::interrupt::get_level() - ); - - (&BUTTON).lock(|data| { - let mut button = data.borrow_mut(); - let button = button.as_mut().unwrap(); - button.clear_interrupt(); - }); - } + esp_println::println!( + "GPIO Interrupt with priority {}", + xtensa_lx::interrupt::get_level() + ); + critical_section::with(|cs| { + BUTTON + .borrow_ref_mut(cs) + .as_mut() + .unwrap() + .clear_interrupt() + }); } diff --git a/esp32s2-hal/examples/hello_rgb.rs b/esp32s2-hal/examples/hello_rgb.rs index 28526d388..aca4b7ddb 100644 --- a/esp32s2-hal/examples/hello_rgb.rs +++ b/esp32s2-hal/examples/hello_rgb.rs @@ -23,7 +23,7 @@ use esp32s2_hal::{ IO, }; #[allow(unused_imports)] -use panic_halt as _; +use esp_backtrace as _; use smart_leds::{ brightness, gamma, diff --git a/esp32s2-hal/examples/hello_world.rs b/esp32s2-hal/examples/hello_world.rs index cd1b4e19a..7e71719fb 100644 --- a/esp32s2-hal/examples/hello_world.rs +++ b/esp32s2-hal/examples/hello_world.rs @@ -14,8 +14,8 @@ use esp32s2_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s2-hal/examples/i2c_display.rs b/esp32s2-hal/examples/i2c_display.rs index d84be9e8e..c640bdef0 100644 --- a/esp32s2-hal/examples/i2c_display.rs +++ b/esp32s2-hal/examples/i2c_display.rs @@ -31,8 +31,8 @@ use esp32s2_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use ssd1306::{prelude::*, I2CDisplayInterface, Ssd1306}; use xtensa_lx_rt::entry; diff --git a/esp32s2-hal/examples/ledc.rs b/esp32s2-hal/examples/ledc.rs index 7ea1c5c78..4d1cff871 100644 --- a/esp32s2-hal/examples/ledc.rs +++ b/esp32s2-hal/examples/ledc.rs @@ -22,8 +22,8 @@ use esp32s2_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use esp_println; -use panic_halt as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s2-hal/examples/pulse_control.rs b/esp32s2-hal/examples/pulse_control.rs index 9baa72d4f..4f5a968b4 100644 --- a/esp32s2-hal/examples/pulse_control.rs +++ b/esp32s2-hal/examples/pulse_control.rs @@ -15,7 +15,7 @@ use esp32s2_hal::{ PulseControl, Rtc, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s2-hal/examples/ram.rs b/esp32s2-hal/examples/ram.rs index 943839dc8..39d0ef60f 100644 --- a/esp32s2-hal/examples/ram.rs +++ b/esp32s2-hal/examples/ram.rs @@ -18,8 +18,8 @@ use esp32s2_hal::{ timer::TimerGroup, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use xtensa_lx_rt::entry; #[ram(rtc_fast)] diff --git a/esp32s2-hal/examples/read_efuse.rs b/esp32s2-hal/examples/read_efuse.rs index bb5325d84..45c8a6e8b 100644 --- a/esp32s2-hal/examples/read_efuse.rs +++ b/esp32s2-hal/examples/read_efuse.rs @@ -15,7 +15,7 @@ use esp32s2_hal::{ Rtc, Serial, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s2-hal/examples/rtc_watchdog.rs b/esp32s2-hal/examples/rtc_watchdog.rs index aa3b80d28..f8ade6095 100644 --- a/esp32s2-hal/examples/rtc_watchdog.rs +++ b/esp32s2-hal/examples/rtc_watchdog.rs @@ -8,6 +8,7 @@ use core::cell::RefCell; +use critical_section::Mutex; use esp32s2_hal::{ clock::ClockControl, interrupt, @@ -16,12 +17,10 @@ use esp32s2_hal::{ Rtc, Rwdt, }; -use panic_halt as _; -use xtensa_lx::mutex::{CriticalSectionMutex, Mutex}; +use esp_backtrace as _; use xtensa_lx_rt::entry; -static mut RWDT: CriticalSectionMutex>> = - CriticalSectionMutex::new(RefCell::new(None)); +static RWDT: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -37,30 +36,23 @@ fn main() -> ! { rtc.rwdt.start(2000u64.millis()); rtc.rwdt.listen(); - interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap(); + critical_section::with(|cs| RWDT.borrow_ref_mut(cs).replace(rtc.rwdt)); - unsafe { - (&RWDT).lock(|data| (*data).replace(Some(rtc.rwdt))); - } + interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap(); loop {} } #[interrupt] fn RTC_CORE() { - unsafe { - (&RWDT).lock(|data| { - esp_println::println!("RWDT Interrupt"); + critical_section::with(|cs| { + let mut rwdt = RWDT.borrow_ref_mut(cs); + let rwdt = rwdt.as_mut().unwrap(); + rwdt.clear_interrupt(); - let mut rwdt = data.borrow_mut(); - let rwdt = rwdt.as_mut().unwrap(); + esp_println::println!("Restarting in 5 seconds..."); - rwdt.clear_interrupt(); - - esp_println::println!("Restarting in 5 seconds..."); - - rwdt.start(5000u64.millis()); - rwdt.unlisten(); - }); - } + rwdt.start(5000u64.millis()); + rwdt.unlisten(); + }); } diff --git a/esp32s2-hal/examples/serial_interrupts.rs b/esp32s2-hal/examples/serial_interrupts.rs index ec932a9bc..f7bb32b10 100644 --- a/esp32s2-hal/examples/serial_interrupts.rs +++ b/esp32s2-hal/examples/serial_interrupts.rs @@ -7,6 +7,7 @@ use core::{cell::RefCell, fmt::Write}; +use critical_section::Mutex; use esp32s2_hal::{ clock::ClockControl, interrupt, @@ -17,13 +18,11 @@ use esp32s2_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; -use xtensa_lx::mutex::{CriticalSectionMutex, Mutex}; use xtensa_lx_rt::entry; -static mut SERIAL: CriticalSectionMutex>>> = - CriticalSectionMutex::new(RefCell::new(None)); +static SERIAL: Mutex>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -56,18 +55,14 @@ fn main() -> ! { timer0.start(1u64.secs()); - unsafe { - (&SERIAL).lock(|data| (*data).replace(Some(serial0))); - } + critical_section::with(|cs| SERIAL.borrow_ref_mut(cs).replace(serial0)); loop { - unsafe { - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); - writeln!(serial, "Hello World! Send a single `#` character or send at least 30 characters and see the interrupts trigger.").ok(); - }); - } + critical_section::with(|cs| { + let mut serial = SERIAL.borrow_ref_mut(cs); + let serial = serial.as_mut().unwrap(); + writeln!(serial, "Hello World! Send a single `#` character or send at least 30 characters and see the interrupts trigger.").ok(); + }); block!(timer0.wait()).unwrap(); } @@ -75,27 +70,25 @@ fn main() -> ! { #[interrupt] fn UART0() { - unsafe { - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); + critical_section::with(|cs| { + let mut serial = SERIAL.borrow_ref_mut(cs); + let serial = serial.as_mut().unwrap(); - let mut cnt = 0; - while let nb::Result::Ok(_c) = serial.read() { - cnt += 1; - } - writeln!(serial, "Read {} bytes", cnt,).ok(); + let mut cnt = 0; + while let nb::Result::Ok(_c) = serial.read() { + cnt += 1; + } + writeln!(serial, "Read {} bytes", cnt,).ok(); - writeln!( - serial, - "Interrupt AT-CMD: {} RX-FIFO-FULL: {}", - serial.at_cmd_interrupt_set(), - serial.rx_fifo_full_interrupt_set(), - ) - .ok(); + writeln!( + serial, + "Interrupt AT-CMD: {} RX-FIFO-FULL: {}", + serial.at_cmd_interrupt_set(), + serial.rx_fifo_full_interrupt_set(), + ) + .ok(); - serial.reset_at_cmd_interrupt(); - serial.reset_rx_fifo_full_interrupt(); - }); - } + serial.reset_at_cmd_interrupt(); + serial.reset_rx_fifo_full_interrupt(); + }); } diff --git a/esp32s2-hal/examples/spi_eh1_loopback.rs b/esp32s2-hal/examples/spi_eh1_loopback.rs index 54a76856c..09a7c03e5 100644 --- a/esp32s2-hal/examples/spi_eh1_loopback.rs +++ b/esp32s2-hal/examples/spi_eh1_loopback.rs @@ -30,7 +30,7 @@ use esp32s2_hal::{ Rtc, Serial, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s2-hal/examples/spi_loopback.rs b/esp32s2-hal/examples/spi_loopback.rs index d2d50ecb6..32bc63ce7 100644 --- a/esp32s2-hal/examples/spi_loopback.rs +++ b/esp32s2-hal/examples/spi_loopback.rs @@ -29,7 +29,7 @@ use esp32s2_hal::{ Rtc, Serial, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s2-hal/examples/systimer.rs b/esp32s2-hal/examples/systimer.rs index 0d8896a75..4300fd5fc 100644 --- a/esp32s2-hal/examples/systimer.rs +++ b/esp32s2-hal/examples/systimer.rs @@ -6,6 +6,7 @@ use core::cell::RefCell; +use critical_section::Mutex; use esp32s2_hal::{ clock::ClockControl, interrupt, @@ -17,16 +18,12 @@ use esp32s2_hal::{ Delay, Rtc, }; -use panic_halt as _; -use xtensa_lx::mutex::{CriticalSectionMutex, Mutex}; +use esp_backtrace as _; use xtensa_lx_rt::entry; -static mut ALARM0: CriticalSectionMutex>>> = - CriticalSectionMutex::new(RefCell::new(None)); -static mut ALARM1: CriticalSectionMutex>>> = - CriticalSectionMutex::new(RefCell::new(None)); -static mut ALARM2: CriticalSectionMutex>>> = - CriticalSectionMutex::new(RefCell::new(None)); +static ALARM0: Mutex>>> = Mutex::new(RefCell::new(None)); +static ALARM1: Mutex>>> = Mutex::new(RefCell::new(None)); +static ALARM2: Mutex>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -56,11 +53,11 @@ fn main() -> ! { alarm2.set_target(42_222_2220 * 2); alarm2.enable_interrupt(); - unsafe { - (&ALARM0).lock(|data| (*data).replace(Some(alarm0))); - (&ALARM1).lock(|data| (*data).replace(Some(alarm1))); - (&ALARM2).lock(|data| (*data).replace(Some(alarm2))); - } + critical_section::with(|cs| { + ALARM0.borrow_ref_mut(cs).replace(alarm0); + ALARM1.borrow_ref_mut(cs).replace(alarm1); + ALARM2.borrow_ref_mut(cs).replace(alarm2); + }); interrupt::enable(pac::Interrupt::SYSTIMER_TARGET0, Priority::Priority1).unwrap(); interrupt::enable(pac::Interrupt::SYSTIMER_TARGET1, Priority::Priority2).unwrap(); @@ -78,38 +75,35 @@ fn main() -> ! { #[interrupt] fn SYSTIMER_TARGET0() { esp_println::println!("Interrupt lvl1 (alarm0)"); - - unsafe { - (&ALARM0).lock(|data| { - let mut alarm = data.borrow_mut(); - let alarm = alarm.as_mut().unwrap(); - alarm.clear_interrupt(); - }); - } + critical_section::with(|cs| { + ALARM0 + .borrow_ref_mut(cs) + .as_mut() + .unwrap() + .clear_interrupt() + }); } #[interrupt] fn SYSTIMER_TARGET1() { esp_println::println!("Interrupt lvl2 (alarm1)"); - - unsafe { - (&ALARM1).lock(|data| { - let mut alarm = data.borrow_mut(); - let alarm = alarm.as_mut().unwrap(); - alarm.clear_interrupt(); - }); - } + critical_section::with(|cs| { + ALARM1 + .borrow_ref_mut(cs) + .as_mut() + .unwrap() + .clear_interrupt() + }); } #[interrupt] fn SYSTIMER_TARGET2() { esp_println::println!("Interrupt lvl2 (alarm2)"); - - unsafe { - (&ALARM2).lock(|data| { - let mut alarm = data.borrow_mut(); - let alarm = alarm.as_mut().unwrap(); - alarm.clear_interrupt(); - }); - } + critical_section::with(|cs| { + ALARM2 + .borrow_ref_mut(cs) + .as_mut() + .unwrap() + .clear_interrupt() + }); } diff --git a/esp32s2-hal/examples/timer_interrupt.rs b/esp32s2-hal/examples/timer_interrupt.rs index 32382f43c..012935249 100644 --- a/esp32s2-hal/examples/timer_interrupt.rs +++ b/esp32s2-hal/examples/timer_interrupt.rs @@ -5,32 +5,25 @@ #![no_std] #![no_main] -use core::{cell::RefCell, fmt::Write}; +use core::cell::RefCell; +use critical_section::Mutex; use esp32s2_hal::{ clock::ClockControl, interrupt, interrupt::Priority, - pac::{self, Peripherals, TIMG0, TIMG1, UART0}, + pac::{self, Peripherals, TIMG0, TIMG1}, prelude::*, timer::{Timer, Timer0, Timer1, TimerGroup}, Rtc, - Serial, }; -use panic_halt as _; -use xtensa_lx::mutex::{CriticalSectionMutex, Mutex}; +use esp_backtrace as _; use xtensa_lx_rt::entry; -static mut SERIAL: CriticalSectionMutex>>> = - CriticalSectionMutex::new(RefCell::new(None)); -static mut TIMER00: CriticalSectionMutex>>>> = - CriticalSectionMutex::new(RefCell::new(None)); -static mut TIMER01: CriticalSectionMutex>>>> = - CriticalSectionMutex::new(RefCell::new(None)); -static mut TIMER10: CriticalSectionMutex>>>> = - CriticalSectionMutex::new(RefCell::new(None)); -static mut TIMER11: CriticalSectionMutex>>>> = - CriticalSectionMutex::new(RefCell::new(None)); +static TIMER00: Mutex>>>> = Mutex::new(RefCell::new(None)); +static TIMER01: Mutex>>>> = Mutex::new(RefCell::new(None)); +static TIMER10: Mutex>>>> = Mutex::new(RefCell::new(None)); +static TIMER11: Mutex>>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -49,7 +42,6 @@ fn main() -> ! { let mut timer11 = timer_group1.timer1; let mut wdt1 = timer_group1.wdt; - let serial0 = Serial::new(peripherals.UART0); let mut rtc = Rtc::new(peripherals.RTC_CNTL); // Disable MWDT and RWDT (Watchdog) flash boot protection @@ -70,97 +62,68 @@ fn main() -> ! { timer11.start(3u64.secs()); timer11.listen(); - unsafe { - (&SERIAL).lock(|data| (*data).replace(Some(serial0))); - (&TIMER00).lock(|data| (*data).replace(Some(timer00))); - (&TIMER01).lock(|data| (*data).replace(Some(timer01))); - (&TIMER10).lock(|data| (*data).replace(Some(timer10))); - (&TIMER11).lock(|data| (*data).replace(Some(timer11))); - } + critical_section::with(|cs| { + TIMER00.borrow_ref_mut(cs).replace(timer00); + TIMER01.borrow_ref_mut(cs).replace(timer01); + TIMER10.borrow_ref_mut(cs).replace(timer10); + TIMER11.borrow_ref_mut(cs).replace(timer11); + }); loop {} } #[interrupt] fn TG0_T0_LEVEL() { - unsafe { - (&TIMER00).lock(|data| { - let mut timer = data.borrow_mut(); - let timer = timer.as_mut().unwrap(); + critical_section::with(|cs| { + let mut timer = TIMER00.borrow_ref_mut(cs); + let timer = timer.as_mut().unwrap(); - if timer.is_interrupt_set() { - timer.clear_interrupt(); - timer.start(500u64.millis()); - - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); - writeln!(serial, "Interrupt Level 2 - Timer0").ok(); - }); - } - }); - } + if timer.is_interrupt_set() { + timer.clear_interrupt(); + timer.start(500u64.millis()); + esp_println::println!("Interrupt Level 2 - Timer0"); + } + }); } #[interrupt] fn TG0_T1_LEVEL() { - unsafe { - (&TIMER01).lock(|data| { - let mut timer = data.borrow_mut(); - let timer = timer.as_mut().unwrap(); + critical_section::with(|cs| { + let mut timer = TIMER01.borrow_ref_mut(cs); + let timer = timer.as_mut().unwrap(); - if timer.is_interrupt_set() { - timer.clear_interrupt(); - timer.start(2500u64.millis()); - - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); - writeln!(serial, "Interrupt Level 2 - Timer1").ok(); - }); - } - }); - } + if timer.is_interrupt_set() { + timer.clear_interrupt(); + timer.start(500u64.millis()); + esp_println::println!("Interrupt Level 2 - Timer1"); + } + }); } #[interrupt] fn TG1_T0_LEVEL() { - unsafe { - (&TIMER10).lock(|data| { - let mut timer = data.borrow_mut(); - let timer = timer.as_mut().unwrap(); + critical_section::with(|cs| { + let mut timer = TIMER10.borrow_ref_mut(cs); + let timer = timer.as_mut().unwrap(); - if timer.is_interrupt_set() { - timer.clear_interrupt(); - timer.start(1u64.secs()); - - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); - writeln!(serial, "Interrupt Level 3 - Timer0").ok(); - }); - } - }); - } + if timer.is_interrupt_set() { + timer.clear_interrupt(); + timer.start(500u64.millis()); + esp_println::println!("Interrupt Level 3 - Timer0"); + } + }); } #[interrupt] fn TG1_T1_LEVEL() { - unsafe { - (&TIMER11).lock(|data| { - let mut timer = data.borrow_mut(); - let timer = timer.as_mut().unwrap(); + critical_section::with(|cs| { + let mut timer = TIMER11.borrow_ref_mut(cs); + let timer = timer.as_mut().unwrap(); - if timer.is_interrupt_set() { - timer.clear_interrupt(); - timer.start(3u64.secs()); - - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); - writeln!(serial, "Interrupt Level 3 - Timer1").ok(); - }); - } - }); - } + if timer.is_interrupt_set() { + timer.clear_interrupt(); + timer.start(500u64.millis()); + esp_println::println!("Interrupt Level 3 - Timer1"); + } + }); } diff --git a/esp32s2-hal/examples/watchdog.rs b/esp32s2-hal/examples/watchdog.rs index b0d34a51f..a7742bfcd 100644 --- a/esp32s2-hal/examples/watchdog.rs +++ b/esp32s2-hal/examples/watchdog.rs @@ -15,8 +15,8 @@ use esp32s2_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s3-hal/Cargo.toml b/esp32s3-hal/Cargo.toml index b04ef8332..c7c68a727 100644 --- a/esp32s3-hal/Cargo.toml +++ b/esp32s3-hal/Cargo.toml @@ -41,6 +41,8 @@ panic-halt = "0.2" ssd1306 = "0.7" smart-leds = "0.3" esp-println = { version = "0.2.0", features = ["esp32s3"] } +esp-backtrace = { version = "0.2", features = ["esp32s3", "panic-handler", "exception-handler", "print-uart"] } +critical-section = "1" [features] default = ["rt", "vectored"] diff --git a/esp32s3-hal/examples/advanced_serial.rs b/esp32s3-hal/examples/advanced_serial.rs index 65cbf5676..d8927ac4a 100644 --- a/esp32s3-hal/examples/advanced_serial.rs +++ b/esp32s3-hal/examples/advanced_serial.rs @@ -21,8 +21,8 @@ use esp32s3_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use esp_println::println; -use panic_halt as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s3-hal/examples/blinky.rs b/esp32s3-hal/examples/blinky.rs index c21515c6b..33d51a856 100644 --- a/esp32s3-hal/examples/blinky.rs +++ b/esp32s3-hal/examples/blinky.rs @@ -14,7 +14,7 @@ use esp32s3_hal::{ Delay, Rtc, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s3-hal/examples/clock_monitor.rs b/esp32s3-hal/examples/clock_monitor.rs index 50b2d7ae9..098343dca 100644 --- a/esp32s3-hal/examples/clock_monitor.rs +++ b/esp32s3-hal/examples/clock_monitor.rs @@ -7,6 +7,7 @@ use core::cell::RefCell; +use critical_section::Mutex; use esp32s3_hal::{ clock::ClockControl, interrupt, @@ -14,12 +15,10 @@ use esp32s3_hal::{ prelude::*, Rtc, }; -use panic_halt as _; -use xtensa_lx::mutex::{CriticalSectionMutex, Mutex}; +use esp_backtrace as _; use xtensa_lx_rt::entry; -static mut RTC: CriticalSectionMutex>> = - CriticalSectionMutex::new(RefCell::new(None)); +static RTC: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -29,8 +28,7 @@ fn main() -> ! { let mut rtc = Rtc::new(peripherals.RTC_CNTL); - // Disable watchdog timers - rtc.swd.disable(); + // Disable watchdog timer rtc.rwdt.disable(); rtc.rwdt.start(2000u64.millis()); @@ -44,27 +42,23 @@ fn main() -> ! { interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap(); - unsafe { - (&RTC).lock(|data| (*data).replace(Some(rtc))); - } + critical_section::with(|cs| RTC.borrow_ref_mut(cs).replace(rtc)); loop {} } #[interrupt] fn RTC_CORE() { - unsafe { - (&RTC).lock(|data| { - let mut rtc = data.borrow_mut(); - let rtc = rtc.as_mut().unwrap(); + critical_section::with(|cs| { + let mut rtc = RTC.borrow_ref_mut(cs); + let rtc = rtc.as_mut().unwrap(); - esp_println::println!( - "{: <10} XTAL frequency: {} MHz", - "[Monitor]", - rtc.estimate_xtal_frequency() - ); + esp_println::println!( + "{: <10} XTAL frequency: {} MHz", + "[Monitor]", + rtc.estimate_xtal_frequency() + ); - rtc.rwdt.clear_interrupt(); - }); - } + rtc.rwdt.clear_interrupt(); + }); } diff --git a/esp32s3-hal/examples/gpio_interrupt.rs b/esp32s3-hal/examples/gpio_interrupt.rs index 1b5fbb274..cfe7609eb 100644 --- a/esp32s3-hal/examples/gpio_interrupt.rs +++ b/esp32s3-hal/examples/gpio_interrupt.rs @@ -8,6 +8,7 @@ use core::cell::RefCell; +use critical_section::Mutex; use esp32s3_hal::{ clock::ClockControl, gpio::{Gpio0, IO}, @@ -20,12 +21,10 @@ use esp32s3_hal::{ Delay, Rtc, }; -use panic_halt as _; -use xtensa_lx::mutex::{Mutex, SpinLockMutex}; +use esp_backtrace as _; use xtensa_lx_rt::entry; -static mut BUTTON: SpinLockMutex>>>> = - SpinLockMutex::new(RefCell::new(None)); +static BUTTON: Mutex>>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -48,9 +47,7 @@ fn main() -> ! { let mut button = io.pins.gpio0.into_pull_down_input(); button.listen(Event::FallingEdge); - unsafe { - (&BUTTON).lock(|data| (*data).replace(Some(button))); - } + critical_section::with(|cs| BUTTON.borrow_ref_mut(cs).replace(button)); interrupt::enable(pac::Interrupt::GPIO, interrupt::Priority::Priority2).unwrap(); @@ -69,16 +66,16 @@ fn main() -> ! { #[ram] #[interrupt] fn GPIO() { - unsafe { - esp_println::println!( - "GPIO Interrupt with priority {}", - xtensa_lx::interrupt::get_level() - ); + esp_println::println!( + "GPIO Interrupt with priority {}", + xtensa_lx::interrupt::get_level() + ); - (&BUTTON).lock(|data| { - let mut button = data.borrow_mut(); - let button = button.as_mut().unwrap(); - button.clear_interrupt(); - }); - } + critical_section::with(|cs| { + BUTTON + .borrow_ref_mut(cs) + .as_mut() + .unwrap() + .clear_interrupt() + }); } diff --git a/esp32s3-hal/examples/hello_rgb.rs b/esp32s3-hal/examples/hello_rgb.rs index c0b201f3c..e7c9c9728 100644 --- a/esp32s3-hal/examples/hello_rgb.rs +++ b/esp32s3-hal/examples/hello_rgb.rs @@ -24,7 +24,7 @@ use esp32s3_hal::{ IO, }; #[allow(unused_imports)] -use panic_halt as _; +use esp_backtrace as _; use smart_leds::{ brightness, gamma, diff --git a/esp32s3-hal/examples/hello_world.rs b/esp32s3-hal/examples/hello_world.rs index 546ce3e51..9ab714e9d 100644 --- a/esp32s3-hal/examples/hello_world.rs +++ b/esp32s3-hal/examples/hello_world.rs @@ -14,8 +14,8 @@ use esp32s3_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s3-hal/examples/i2c_display.rs b/esp32s3-hal/examples/i2c_display.rs index 0aafbaefe..b4b6f58e8 100644 --- a/esp32s3-hal/examples/i2c_display.rs +++ b/esp32s3-hal/examples/i2c_display.rs @@ -31,8 +31,8 @@ use esp32s3_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use ssd1306::{prelude::*, I2CDisplayInterface, Ssd1306}; use xtensa_lx_rt::entry; diff --git a/esp32s3-hal/examples/ledc.rs b/esp32s3-hal/examples/ledc.rs index 045df5273..b0a02e48d 100644 --- a/esp32s3-hal/examples/ledc.rs +++ b/esp32s3-hal/examples/ledc.rs @@ -22,8 +22,8 @@ use esp32s3_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use esp_println; -use panic_halt as _; use xtensa_lx_rt::entry; #[entry] @@ -53,7 +53,7 @@ fn main() -> ! { let mut lstimer0 = ledc.get_timer::(timer::Number::Timer0); - let res = lstimer0 + lstimer0 .configure(timer::config::Config { duty: timer::config::Duty::Duty5Bit, clock_source: timer::LSClockSource::APBClk, diff --git a/esp32s3-hal/examples/multicore.rs b/esp32s3-hal/examples/multicore.rs index 8e82060a2..dc374908d 100644 --- a/esp32s3-hal/examples/multicore.rs +++ b/esp32s3-hal/examples/multicore.rs @@ -5,8 +5,9 @@ #![no_std] #![no_main] -use core::sync::atomic::{AtomicI32, Ordering}; +use core::cell::RefCell; +use critical_section::Mutex; use esp32s3_hal::{ clock::ClockControl, pac::{Peripherals, TIMG1}, @@ -15,10 +16,9 @@ use esp32s3_hal::{ CpuControl, Rtc, }; +use esp_backtrace as _; use esp_println::println; use nb::block; -use panic_halt as _; -use xtensa_lx::mutex::Mutex; use xtensa_lx_rt::entry; #[entry] @@ -45,7 +45,7 @@ fn main() -> ! { timer0.start(1u64.secs()); timer1.start(500u64.millis()); - let counter = xtensa_lx::mutex::SpinLockMutex::new(AtomicI32::new(0)); + let counter = Mutex::new(RefCell::new(0)); let mut cpu_control = CpuControl::new(system.cpu_control); let mut cpu1_fnctn = || { @@ -56,24 +56,19 @@ fn main() -> ! { loop { block!(timer0.wait()).unwrap(); - let count = (&counter).lock(|counter| counter.load(Ordering::Relaxed)); + let count = critical_section::with(|cs| *counter.borrow_ref(cs)); println!("Hello World - Core 0! Counter is {}", count); } } fn cpu1_task( timer: &mut Timer>, - counter: &xtensa_lx::mutex::SpinLockMutex, + counter: &critical_section::Mutex>, ) -> ! { println!("Hello World - Core 1!"); loop { block!(timer.wait()).unwrap(); - (&*counter).lock(|counter| { - counter.store( - counter.load(Ordering::Relaxed).wrapping_add(1), - Ordering::Relaxed, - ); - }); + critical_section::with(|cs| counter.borrow_ref_mut(cs).wrapping_add(1)); } } diff --git a/esp32s3-hal/examples/pulse_control.rs b/esp32s3-hal/examples/pulse_control.rs index 5e77a4f44..9f2bbe2a1 100644 --- a/esp32s3-hal/examples/pulse_control.rs +++ b/esp32s3-hal/examples/pulse_control.rs @@ -15,7 +15,7 @@ use esp32s3_hal::{ PulseControl, Rtc, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s3-hal/examples/ram.rs b/esp32s3-hal/examples/ram.rs index 97f828dd5..3311d6999 100644 --- a/esp32s3-hal/examples/ram.rs +++ b/esp32s3-hal/examples/ram.rs @@ -18,8 +18,8 @@ use esp32s3_hal::{ timer::TimerGroup, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use xtensa_lx_rt::entry; #[ram(rtc_fast)] diff --git a/esp32s3-hal/examples/read_efuse.rs b/esp32s3-hal/examples/read_efuse.rs index c6a4e1742..45aa4ce35 100644 --- a/esp32s3-hal/examples/read_efuse.rs +++ b/esp32s3-hal/examples/read_efuse.rs @@ -15,7 +15,7 @@ use esp32s3_hal::{ Rtc, Serial, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s3-hal/examples/rtc_watchdog.rs b/esp32s3-hal/examples/rtc_watchdog.rs index a44078377..23495d2aa 100644 --- a/esp32s3-hal/examples/rtc_watchdog.rs +++ b/esp32s3-hal/examples/rtc_watchdog.rs @@ -8,6 +8,7 @@ use core::cell::RefCell; +use critical_section::Mutex; use esp32s3_hal::{ clock::ClockControl, interrupt, @@ -16,12 +17,10 @@ use esp32s3_hal::{ Rtc, Rwdt, }; -use panic_halt as _; -use xtensa_lx::mutex::{CriticalSectionMutex, Mutex}; +use esp_backtrace as _; use xtensa_lx_rt::entry; -static mut RWDT: CriticalSectionMutex>> = - CriticalSectionMutex::new(RefCell::new(None)); +static RWDT: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -31,37 +30,29 @@ fn main() -> ! { let mut rtc = Rtc::new(peripherals.RTC_CNTL); - // Disable watchdog timers - rtc.swd.disable(); + // Disable watchdog timer rtc.rwdt.disable(); rtc.rwdt.start(2000u64.millis()); rtc.rwdt.listen(); - interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap(); + critical_section::with(|cs| RWDT.borrow_ref_mut(cs).replace(rtc.rwdt)); - unsafe { - (&RWDT).lock(|data| (*data).replace(Some(rtc.rwdt))); - } + interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap(); loop {} } #[interrupt] fn RTC_CORE() { - unsafe { - (&RWDT).lock(|data| { - esp_println::println!("RWDT Interrupt"); + critical_section::with(|cs| { + let mut rwdt = RWDT.borrow_ref_mut(cs); + let rwdt = rwdt.as_mut().unwrap(); + rwdt.clear_interrupt(); - let mut rwdt = data.borrow_mut(); - let rwdt = rwdt.as_mut().unwrap(); + esp_println::println!("Restarting in 5 seconds..."); - rwdt.clear_interrupt(); - - esp_println::println!("Restarting in 5 seconds..."); - - rwdt.start(5000u64.millis()); - rwdt.unlisten(); - }); - } + rwdt.start(5000u64.millis()); + rwdt.unlisten(); + }); } diff --git a/esp32s3-hal/examples/serial_interrupts.rs b/esp32s3-hal/examples/serial_interrupts.rs index ea94bc02a..ce57e8d14 100644 --- a/esp32s3-hal/examples/serial_interrupts.rs +++ b/esp32s3-hal/examples/serial_interrupts.rs @@ -7,6 +7,7 @@ use core::{cell::RefCell, fmt::Write}; +use critical_section::Mutex; use esp32s3_hal::{ clock::ClockControl, interrupt, @@ -17,13 +18,11 @@ use esp32s3_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; -use xtensa_lx::mutex::{Mutex, SpinLockMutex}; use xtensa_lx_rt::entry; -static mut SERIAL: SpinLockMutex>>> = - SpinLockMutex::new(RefCell::new(None)); +static SERIAL: Mutex>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -56,18 +55,14 @@ fn main() -> ! { timer0.start(1u64.secs()); - unsafe { - (&SERIAL).lock(|data| (*data).replace(Some(serial0))); - } + critical_section::with(|cs| SERIAL.borrow_ref_mut(cs).replace(serial0)); loop { - unsafe { - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); - writeln!(serial, "Hello World! Send a single `#` character or send at least 30 characters and see the interrupts trigger.").ok(); - }); - } + critical_section::with(|cs| { + let mut serial = SERIAL.borrow_ref_mut(cs); + let serial = serial.as_mut().unwrap(); + writeln!(serial, "Hello World! Send a single `#` character or send at least 30 characters and see the interrupts trigger.").ok(); + }); block!(timer0.wait()).unwrap(); } @@ -75,27 +70,25 @@ fn main() -> ! { #[interrupt] fn UART0() { - unsafe { - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); + critical_section::with(|cs| { + let mut serial = SERIAL.borrow_ref_mut(cs); + let serial = serial.as_mut().unwrap(); - let mut cnt = 0; - while let nb::Result::Ok(_c) = serial.read() { - cnt += 1; - } - writeln!(serial, "Read {} bytes", cnt,).ok(); + let mut cnt = 0; + while let nb::Result::Ok(_c) = serial.read() { + cnt += 1; + } + writeln!(serial, "Read {} bytes", cnt,).ok(); - writeln!( - serial, - "Interrupt AT-CMD: {} RX-FIFO-FULL: {}", - serial.at_cmd_interrupt_set(), - serial.rx_fifo_full_interrupt_set(), - ) - .ok(); + writeln!( + serial, + "Interrupt AT-CMD: {} RX-FIFO-FULL: {}", + serial.at_cmd_interrupt_set(), + serial.rx_fifo_full_interrupt_set(), + ) + .ok(); - serial.reset_at_cmd_interrupt(); - serial.reset_rx_fifo_full_interrupt(); - }); - } + serial.reset_at_cmd_interrupt(); + serial.reset_rx_fifo_full_interrupt(); + }); } diff --git a/esp32s3-hal/examples/spi_eh1_loopback.rs b/esp32s3-hal/examples/spi_eh1_loopback.rs index 3e4643935..c7b800d55 100644 --- a/esp32s3-hal/examples/spi_eh1_loopback.rs +++ b/esp32s3-hal/examples/spi_eh1_loopback.rs @@ -18,6 +18,7 @@ use core::fmt::Write; +use embedded_hal_1::spi::blocking::SpiBus; use esp32s3_hal::{ clock::ClockControl, gpio::IO, @@ -29,11 +30,9 @@ use esp32s3_hal::{ Rtc, Serial, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; -use embedded_hal_1::spi::blocking::SpiBus; - #[entry] fn main() -> ! { let peripherals = Peripherals::take().unwrap(); @@ -82,18 +81,17 @@ fn main() -> ! { writeln!(serial0, " SUCCESS").unwrap(); delay.delay_ms(250u32); - // --- Asymmetric transfer (Read more than we write) --- write!(serial0, "Starting asymetric transfer (read > write)...").unwrap(); let mut read: [u8; 4] = [0x00; 4]; - SpiBus::transfer(&mut spi, &mut read[0..2], &write[..]).expect("Asymmetric transfer failed"); + SpiBus::transfer(&mut spi, &mut read[0..2], &write[..]) + .expect("Asymmetric transfer failed"); assert_eq!(write[0], read[0]); assert_eq!(read[2], 0x00u8); writeln!(serial0, " SUCCESS").unwrap(); delay.delay_ms(250u32); - // --- Symmetric transfer with huge buffer --- // Only your RAM is the limit! write!(serial0, "Starting huge transfer...").unwrap(); @@ -108,8 +106,8 @@ fn main() -> ! { writeln!(serial0, " SUCCESS").unwrap(); delay.delay_ms(250u32); - - // --- Symmetric transfer with huge buffer in-place (No additional allocation needed) --- + // --- Symmetric transfer with huge buffer in-place (No additional allocation + // needed) --- write!(serial0, "Starting huge transfer (in-place)...").unwrap(); let mut write = [0x55u8; 4096]; for byte in 0..write.len() { @@ -124,4 +122,3 @@ fn main() -> ! { delay.delay_ms(250u32); } } - diff --git a/esp32s3-hal/examples/spi_loopback.rs b/esp32s3-hal/examples/spi_loopback.rs index aea91bc88..4c3e38c75 100644 --- a/esp32s3-hal/examples/spi_loopback.rs +++ b/esp32s3-hal/examples/spi_loopback.rs @@ -29,7 +29,7 @@ use esp32s3_hal::{ Rtc, Serial, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s3-hal/examples/systimer.rs b/esp32s3-hal/examples/systimer.rs index 4d2448ef2..519466f3c 100644 --- a/esp32s3-hal/examples/systimer.rs +++ b/esp32s3-hal/examples/systimer.rs @@ -6,6 +6,7 @@ use core::cell::RefCell; +use critical_section::Mutex; use esp32s3_hal::{ clock::ClockControl, interrupt, @@ -17,16 +18,12 @@ use esp32s3_hal::{ Delay, Rtc, }; -use panic_halt as _; -use xtensa_lx::mutex::{Mutex, SpinLockMutex}; +use esp_backtrace as _; use xtensa_lx_rt::entry; -static mut ALARM0: SpinLockMutex>>> = - SpinLockMutex::new(RefCell::new(None)); -static mut ALARM1: SpinLockMutex>>> = - SpinLockMutex::new(RefCell::new(None)); -static mut ALARM2: SpinLockMutex>>> = - SpinLockMutex::new(RefCell::new(None)); +static ALARM0: Mutex>>> = Mutex::new(RefCell::new(None)); +static ALARM1: Mutex>>> = Mutex::new(RefCell::new(None)); +static ALARM2: Mutex>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -45,22 +42,22 @@ fn main() -> ! { let syst = SystemTimer::new(peripherals.SYSTIMER); let alarm0 = syst.alarm0; - alarm0.set_target(40_000_000); + alarm0.set_target(40_000_0000); alarm0.enable_interrupt(); let alarm1 = syst.alarm1; - alarm1.set_target(41_111_111); + alarm1.set_target(41_111_1110); alarm1.enable_interrupt(); let alarm2 = syst.alarm2; - alarm2.set_target(42_222_222 * 2); + alarm2.set_target(42_222_2220 * 2); alarm2.enable_interrupt(); - unsafe { - (&ALARM0).lock(|data| (*data).replace(Some(alarm0))); - (&ALARM1).lock(|data| (*data).replace(Some(alarm1))); - (&ALARM2).lock(|data| (*data).replace(Some(alarm2))); - } + critical_section::with(|cs| { + ALARM0.borrow_ref_mut(cs).replace(alarm0); + ALARM1.borrow_ref_mut(cs).replace(alarm1); + ALARM2.borrow_ref_mut(cs).replace(alarm2); + }); interrupt::enable(pac::Interrupt::SYSTIMER_TARGET0, Priority::Priority1).unwrap(); interrupt::enable(pac::Interrupt::SYSTIMER_TARGET1, Priority::Priority2).unwrap(); @@ -78,38 +75,35 @@ fn main() -> ! { #[interrupt] fn SYSTIMER_TARGET0() { esp_println::println!("Interrupt lvl1 (alarm0)"); - - unsafe { - (&ALARM0).lock(|data| { - let mut alarm = data.borrow_mut(); - let alarm = alarm.as_mut().unwrap(); - alarm.clear_interrupt(); - }); - } + critical_section::with(|cs| { + ALARM0 + .borrow_ref_mut(cs) + .as_mut() + .unwrap() + .clear_interrupt() + }); } #[interrupt] fn SYSTIMER_TARGET1() { esp_println::println!("Interrupt lvl2 (alarm1)"); - - unsafe { - (&ALARM1).lock(|data| { - let mut alarm = data.borrow_mut(); - let alarm = alarm.as_mut().unwrap(); - alarm.clear_interrupt(); - }); - } + critical_section::with(|cs| { + ALARM1 + .borrow_ref_mut(cs) + .as_mut() + .unwrap() + .clear_interrupt() + }); } #[interrupt] fn SYSTIMER_TARGET2() { esp_println::println!("Interrupt lvl2 (alarm2)"); - - unsafe { - (&ALARM2).lock(|data| { - let mut alarm = data.borrow_mut(); - let alarm = alarm.as_mut().unwrap(); - alarm.clear_interrupt(); - }); - } + critical_section::with(|cs| { + ALARM2 + .borrow_ref_mut(cs) + .as_mut() + .unwrap() + .clear_interrupt() + }); } diff --git a/esp32s3-hal/examples/timer_interrupt.rs b/esp32s3-hal/examples/timer_interrupt.rs index 588440659..399717b69 100644 --- a/esp32s3-hal/examples/timer_interrupt.rs +++ b/esp32s3-hal/examples/timer_interrupt.rs @@ -5,32 +5,25 @@ #![no_std] #![no_main] -use core::{cell::RefCell, fmt::Write}; +use core::cell::RefCell; +use critical_section::Mutex; use esp32s3_hal::{ clock::ClockControl, interrupt, interrupt::Priority, - pac::{self, Peripherals, TIMG0, TIMG1, UART0}, + pac::{self, Peripherals, TIMG0, TIMG1}, prelude::*, timer::{Timer, Timer0, Timer1, TimerGroup}, Rtc, - Serial, }; -use panic_halt as _; -use xtensa_lx::mutex::{Mutex, SpinLockMutex}; +use esp_backtrace as _; use xtensa_lx_rt::entry; -static mut SERIAL: SpinLockMutex>>> = - SpinLockMutex::new(RefCell::new(None)); -static mut TIMER00: SpinLockMutex>>>> = - SpinLockMutex::new(RefCell::new(None)); -static mut TIMER01: SpinLockMutex>>>> = - SpinLockMutex::new(RefCell::new(None)); -static mut TIMER10: SpinLockMutex>>>> = - SpinLockMutex::new(RefCell::new(None)); -static mut TIMER11: SpinLockMutex>>>> = - SpinLockMutex::new(RefCell::new(None)); +static TIMER00: Mutex>>>> = Mutex::new(RefCell::new(None)); +static TIMER01: Mutex>>>> = Mutex::new(RefCell::new(None)); +static TIMER10: Mutex>>>> = Mutex::new(RefCell::new(None)); +static TIMER11: Mutex>>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { @@ -49,7 +42,6 @@ fn main() -> ! { let mut timer11 = timer_group1.timer1; let mut wdt1 = timer_group1.wdt; - let serial0 = Serial::new(peripherals.UART0); let mut rtc = Rtc::new(peripherals.RTC_CNTL); // Disable MWDT and RWDT (Watchdog) flash boot protection @@ -70,97 +62,68 @@ fn main() -> ! { timer11.start(3u64.secs()); timer11.listen(); - unsafe { - (&SERIAL).lock(|data| (*data).replace(Some(serial0))); - (&TIMER00).lock(|data| (*data).replace(Some(timer00))); - (&TIMER01).lock(|data| (*data).replace(Some(timer01))); - (&TIMER10).lock(|data| (*data).replace(Some(timer10))); - (&TIMER11).lock(|data| (*data).replace(Some(timer11))); - } + critical_section::with(|cs| { + TIMER00.borrow_ref_mut(cs).replace(timer00); + TIMER01.borrow_ref_mut(cs).replace(timer01); + TIMER10.borrow_ref_mut(cs).replace(timer10); + TIMER11.borrow_ref_mut(cs).replace(timer11); + }); loop {} } #[interrupt] fn TG0_T0_LEVEL() { - unsafe { - (&TIMER00).lock(|data| { - let mut timer = data.borrow_mut(); - let timer = timer.as_mut().unwrap(); + critical_section::with(|cs| { + let mut timer = TIMER00.borrow_ref_mut(cs); + let timer = timer.as_mut().unwrap(); - if timer.is_interrupt_set() { - timer.clear_interrupt(); - timer.start(500u64.millis()); - - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); - writeln!(serial, "Interrupt Level 2 - Timer0").ok(); - }); - } - }); - } + if timer.is_interrupt_set() { + timer.clear_interrupt(); + timer.start(500u64.millis()); + esp_println::println!("Interrupt Level 2 - Timer0"); + } + }); } #[interrupt] fn TG0_T1_LEVEL() { - unsafe { - (&TIMER01).lock(|data| { - let mut timer = data.borrow_mut(); - let timer = timer.as_mut().unwrap(); + critical_section::with(|cs| { + let mut timer = TIMER01.borrow_ref_mut(cs); + let timer = timer.as_mut().unwrap(); - if timer.is_interrupt_set() { - timer.clear_interrupt(); - timer.start(2500u64.millis()); - - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); - writeln!(serial, "Interrupt Level 2 - Timer1").ok(); - }); - } - }); - } + if timer.is_interrupt_set() { + timer.clear_interrupt(); + timer.start(500u64.millis()); + esp_println::println!("Interrupt Level 2 - Timer1"); + } + }); } #[interrupt] fn TG1_T0_LEVEL() { - unsafe { - (&TIMER10).lock(|data| { - let mut timer = data.borrow_mut(); - let timer = timer.as_mut().unwrap(); + critical_section::with(|cs| { + let mut timer = TIMER10.borrow_ref_mut(cs); + let timer = timer.as_mut().unwrap(); - if timer.is_interrupt_set() { - timer.clear_interrupt(); - timer.start(1u64.secs()); - - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); - writeln!(serial, "Interrupt Level 3 - Timer0").ok(); - }); - } - }); - } + if timer.is_interrupt_set() { + timer.clear_interrupt(); + timer.start(500u64.millis()); + esp_println::println!("Interrupt Level 3 - Timer0"); + } + }); } #[interrupt] fn TG1_T1_LEVEL() { - unsafe { - (&TIMER11).lock(|data| { - let mut timer = data.borrow_mut(); - let timer = timer.as_mut().unwrap(); + critical_section::with(|cs| { + let mut timer = TIMER11.borrow_ref_mut(cs); + let timer = timer.as_mut().unwrap(); - if timer.is_interrupt_set() { - timer.clear_interrupt(); - timer.start(3u64.secs()); - - (&SERIAL).lock(|data| { - let mut serial = data.borrow_mut(); - let serial = serial.as_mut().unwrap(); - writeln!(serial, "Interrupt Level 3 - Timer1").ok(); - }); - } - }); - } + if timer.is_interrupt_set() { + timer.clear_interrupt(); + timer.start(500u64.millis()); + esp_println::println!("Interrupt Level 3 - Timer1"); + } + }); } diff --git a/esp32s3-hal/examples/usb_serial_jtag.rs b/esp32s3-hal/examples/usb_serial_jtag.rs index c5a24eeb5..944f6d57c 100644 --- a/esp32s3-hal/examples/usb_serial_jtag.rs +++ b/esp32s3-hal/examples/usb_serial_jtag.rs @@ -16,7 +16,7 @@ use esp32s3_hal::{ Rtc, UsbSerialJtag, }; -use panic_halt as _; +use esp_backtrace as _; use xtensa_lx_rt::entry; #[entry] diff --git a/esp32s3-hal/examples/watchdog.rs b/esp32s3-hal/examples/watchdog.rs index b9911c69b..7631757a9 100644 --- a/esp32s3-hal/examples/watchdog.rs +++ b/esp32s3-hal/examples/watchdog.rs @@ -15,8 +15,8 @@ use esp32s3_hal::{ Rtc, Serial, }; +use esp_backtrace as _; use nb::block; -use panic_halt as _; use xtensa_lx_rt::entry; #[entry]