From a6c1e237cc165820c7996dfc00fa6986988c3bd3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Mon, 19 Aug 2024 19:04:52 +0200 Subject: [PATCH 01/19] Rework hal initialization --- esp-hal/src/aes/mod.rs | 18 +- esp-hal/src/analog/adc/mod.rs | 17 +- esp-hal/src/clock/mod.rs | 555 +++++++----------- esp-hal/src/delay.rs | 10 +- esp-hal/src/dma/mod.rs | 122 ++-- esp-hal/src/gpio/mod.rs | 3 +- esp-hal/src/gpio/rtc_io.rs | 19 +- esp-hal/src/i2c.rs | 43 +- esp-hal/src/i2s.rs | 27 +- esp-hal/src/interrupt/mod.rs | 30 +- esp-hal/src/lcd_cam/cam.rs | 9 +- esp-hal/src/lcd_cam/lcd/i8080.rs | 23 +- esp-hal/src/ledc/mod.rs | 14 +- esp-hal/src/lib.rs | 48 +- esp-hal/src/mcpwm/mod.rs | 21 +- esp-hal/src/mcpwm/operator.rs | 10 +- esp-hal/src/prelude.rs | 2 +- esp-hal/src/rmt.rs | 22 +- esp-hal/src/rom/md5.rs | 11 +- esp-hal/src/rtc_cntl/mod.rs | 24 +- esp-hal/src/soc/esp32/efuse/mod.rs | 5 +- esp-hal/src/soc/esp32c2/efuse/mod.rs | 5 +- esp-hal/src/soc/esp32c3/efuse/mod.rs | 5 +- esp-hal/src/soc/esp32c6/efuse/mod.rs | 5 +- esp-hal/src/soc/esp32h2/efuse/mod.rs | 5 +- esp-hal/src/soc/esp32s2/efuse/mod.rs | 5 +- esp-hal/src/soc/esp32s2/ulp_core.rs | 15 +- esp-hal/src/soc/esp32s3/cpu_control.rs | 14 +- esp-hal/src/soc/esp32s3/efuse/mod.rs | 5 +- esp-hal/src/soc/esp32s3/ulp_core.rs | 21 +- esp-hal/src/spi/master.rs | 7 +- esp-hal/src/spi/slave.rs | 11 +- esp-hal/src/system.rs | 74 +-- esp-hal/src/timer/mod.rs | 10 +- esp-hal/src/timer/systimer.rs | 83 +-- esp-hal/src/timer/timg.rs | 13 +- esp-hal/src/twai/mod.rs | 14 +- esp-hal/src/uart.rs | 56 +- esp-hal/src/usb_serial_jtag.rs | 10 +- examples/src/bin/adc.rs | 11 +- examples/src/bin/adc_cal.rs | 11 +- examples/src/bin/advanced_serial.rs | 18 +- examples/src/bin/blinky.rs | 11 +- examples/src/bin/blinky_erased_pins.rs | 11 +- examples/src/bin/dac.rs | 18 +- examples/src/bin/debug_assist.rs | 16 +- examples/src/bin/dma_extmem2mem.rs | 12 +- examples/src/bin/dma_mem2mem.rs | 12 +- examples/src/bin/embassy_hello_world.rs | 15 +- examples/src/bin/embassy_i2c.rs | 18 +- .../embassy_i2c_bmp180_calibration_data.rs | 18 +- examples/src/bin/embassy_i2s_read.rs | 11 +- examples/src/bin/embassy_i2s_sound.rs | 11 +- examples/src/bin/embassy_multicore.rs | 11 +- .../src/bin/embassy_multicore_interrupt.rs | 11 +- examples/src/bin/embassy_multiprio.rs | 12 +- examples/src/bin/embassy_parl_io_rx.rs | 11 +- examples/src/bin/embassy_parl_io_tx.rs | 11 +- examples/src/bin/embassy_rmt_rx.rs | 11 +- examples/src/bin/embassy_rmt_tx.rs | 12 +- examples/src/bin/embassy_serial.rs | 14 +- examples/src/bin/embassy_spi.rs | 11 +- examples/src/bin/embassy_touch.rs | 11 +- examples/src/bin/embassy_twai.rs | 12 +- examples/src/bin/embassy_usb_serial.rs | 11 +- examples/src/bin/embassy_usb_serial_jtag.rs | 11 +- examples/src/bin/embassy_wait.rs | 11 +- examples/src/bin/etm_blinky_systimer.rs | 3 +- examples/src/bin/etm_gpio.rs | 3 +- examples/src/bin/etm_timer.rs | 12 +- examples/src/bin/gpio_interrupt.rs | 11 +- examples/src/bin/hello_rgb.rs | 18 +- examples/src/bin/hello_world.rs | 18 +- examples/src/bin/hmac.rs | 7 +- .../src/bin/i2c_bmp180_calibration_data.rs | 17 +- examples/src/bin/i2c_display.rs | 18 +- examples/src/bin/i2s_read.rs | 11 +- examples/src/bin/i2s_sound.rs | 15 +- .../src/bin/ieee802154_receive_all_frames.rs | 4 +- examples/src/bin/ieee802154_receive_frame.rs | 6 +- .../bin/ieee802154_send_broadcast_frame.rs | 16 +- examples/src/bin/ieee802154_send_frame.rs | 16 +- examples/src/bin/ieee802154_sniffer.rs | 18 +- examples/src/bin/lcd_cam_ov2640.rs | 11 +- examples/src/bin/lcd_i8080.rs | 11 +- examples/src/bin/ledc.rs | 11 +- examples/src/bin/lp_core_basic.rs | 3 +- examples/src/bin/lp_core_i2c.rs | 3 +- examples/src/bin/lp_core_uart.rs | 11 +- examples/src/bin/mcpwm.rs | 11 +- examples/src/bin/multicore.rs | 11 +- examples/src/bin/parl_io_rx.rs | 11 +- examples/src/bin/parl_io_tx.rs | 11 +- examples/src/bin/pcnt_encoder.rs | 5 +- examples/src/bin/psram_octal.rs | 4 +- examples/src/bin/psram_quad.rs | 13 +- examples/src/bin/qspi_flash.rs | 11 +- examples/src/bin/ram.rs | 18 +- examples/src/bin/rmt_rx.rs | 11 +- examples/src/bin/rmt_tx.rs | 11 +- examples/src/bin/rng.rs | 4 +- examples/src/bin/rtc_time.rs | 17 +- examples/src/bin/rtc_watchdog.rs | 13 +- examples/src/bin/serial_interrupts.rs | 12 +- examples/src/bin/sleep_timer.rs | 11 +- examples/src/bin/sleep_timer_ext0.rs | 11 +- examples/src/bin/sleep_timer_ext1.rs | 11 +- examples/src/bin/sleep_timer_lpio.rs | 11 +- examples/src/bin/sleep_timer_rtcio.rs | 11 +- examples/src/bin/software_interrupts.rs | 17 +- .../spi_halfduplex_read_manufacturer_id.rs | 11 +- examples/src/bin/spi_loopback.rs | 11 +- examples/src/bin/spi_loopback_dma.rs | 8 +- examples/src/bin/spi_slave_dma.rs | 11 +- examples/src/bin/systimer.rs | 11 +- examples/src/bin/timer_interrupt.rs | 12 +- examples/src/bin/touch.rs | 11 +- examples/src/bin/twai.rs | 11 +- examples/src/bin/ulp_riscv_core_basic.rs | 3 +- examples/src/bin/usb_serial.rs | 3 +- examples/src/bin/usb_serial_jtag.rs | 18 +- examples/src/bin/watchdog.rs | 17 +- examples/src/bin/wifi_80211_tx.rs | 12 +- examples/src/bin/wifi_access_point.rs | 18 +- .../src/bin/wifi_access_point_with_sta.rs | 18 +- examples/src/bin/wifi_bench.rs | 19 +- examples/src/bin/wifi_ble.rs | 11 +- examples/src/bin/wifi_coex.rs | 18 +- examples/src/bin/wifi_dhcp.rs | 18 +- examples/src/bin/wifi_embassy_access_point.rs | 17 +- .../bin/wifi_embassy_access_point_with_sta.rs | 9 +- examples/src/bin/wifi_embassy_bench.rs | 17 +- examples/src/bin/wifi_embassy_ble.rs | 15 +- examples/src/bin/wifi_embassy_dhcp.rs | 17 +- examples/src/bin/wifi_embassy_esp_now.rs | 17 +- .../src/bin/wifi_embassy_esp_now_duplex.rs | 17 +- examples/src/bin/wifi_esp_now.rs | 18 +- examples/src/bin/wifi_sniffer.rs | 13 +- examples/src/bin/wifi_static_ip.rs | 18 +- hil-test/tests/aes.rs | 4 +- hil-test/tests/aes_dma.rs | 22 +- hil-test/tests/clock_monitor.rs | 14 +- hil-test/tests/delay.rs | 9 +- hil-test/tests/dma_mem2mem.rs | 160 ++--- hil-test/tests/ecc.rs | 19 +- hil-test/tests/embassy_interrupt_executor.rs | 11 +- hil-test/tests/embassy_timers_executors.rs | 98 ++-- hil-test/tests/get_time.rs | 26 +- hil-test/tests/gpio.rs | 20 +- hil-test/tests/i2s.rs | 14 +- hil-test/tests/i2s_async.rs | 14 +- hil-test/tests/interrupt.rs | 17 +- hil-test/tests/lcd_cam_i8080.rs | 39 +- hil-test/tests/lcd_cam_i8080_async.rs | 35 +- hil-test/tests/pcnt.rs | 27 +- hil-test/tests/rmt.rs | 11 +- hil-test/tests/rsa.rs | 3 +- hil-test/tests/sha.rs | 8 +- hil-test/tests/spi_full_duplex.rs | 11 +- hil-test/tests/spi_full_duplex_dma.rs | 8 +- hil-test/tests/spi_full_duplex_dma_async.rs | 10 +- hil-test/tests/spi_half_duplex_read.rs | 8 +- hil-test/tests/spi_half_duplex_write.rs | 8 +- hil-test/tests/systimer.rs | 44 +- hil-test/tests/twai.rs | 40 +- hil-test/tests/uart.rs | 31 +- hil-test/tests/uart_async.rs | 36 +- hil-test/tests/uart_tx_rx.rs | 32 +- hil-test/tests/uart_tx_rx_async.rs | 33 +- hil-test/tests/usb_serial_jtag.rs | 16 +- 170 files changed, 1512 insertions(+), 1937 deletions(-) diff --git a/esp-hal/src/aes/mod.rs b/esp-hal/src/aes/mod.rs index 2d3e7afbd48..cfacc307bc1 100644 --- a/esp-hal/src/aes/mod.rs +++ b/esp-hal/src/aes/mod.rs @@ -28,26 +28,32 @@ //! # let plaintext = b"message"; //! # let mut keybuf = [0_u8; 16]; //! # keybuf[..keytext.len()].copy_from_slice(keytext); -//! let mut block_buf = [0_u8; 16]; -//! block_buf[..plaintext.len()].copy_from_slice(plaintext); -//! let mut block = block_buf.clone(); +//! # +//! let system = esp_hal::init(CpuClock::boot_default()); //! -//! let mut aes = Aes::new(peripherals.AES); +//! let mut block = [0_u8; 16]; +//! block[..plaintext.len()].copy_from_slice(plaintext); +//! +//! let mut aes = Aes::new(system.peripherals.AES); //! aes.process(&mut block, Mode::Encryption128, keybuf); -//! let hw_encrypted = block.clone(); +//! +//! // The encryption happens in-place, so the ciphertext is in `block` //! //! aes.process(&mut block, Mode::Decryption128, keybuf); -//! let hw_decrypted = block; +//! +//! // The decryption happens in-place, so the plaintext is in `block` //! # } //! ``` //! //! ### AES-DMA +//! //! Visit the [AES-DMA] test for a more advanced example of using AES-DMA //! mode. //! //! [AES-DMA]: https://github.com/esp-rs/esp-hal/blob/main/hil-test/tests/aes_dma.rs //! //! ## Implementation State +//! //! * AES-DMA mode is currently not supported on ESP32 and ESP32S2 //! * AES-DMA Initialization Vector (IV) is currently not supported diff --git a/esp-hal/src/analog/adc/mod.rs b/esp-hal/src/analog/adc/mod.rs index a39c337ffb7..b15e1cfa83d 100644 --- a/esp-hal/src/analog/adc/mod.rs +++ b/esp-hal/src/analog/adc/mod.rs @@ -32,8 +32,7 @@ //! # use esp_hal::analog::adc::Adc; //! # use esp_hal::delay::Delay; //! # use esp_hal::gpio::Io; -//! -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); #![cfg_attr(esp32, doc = "let analog_pin = io.pins.gpio32;")] #![cfg_attr(any(esp32s2, esp32s3), doc = "let analog_pin = io.pins.gpio3;")] #![cfg_attr( @@ -41,11 +40,13 @@ doc = "let analog_pin = io.pins.gpio2;" )] //! let mut adc1_config = AdcConfig::new(); -//! let mut pin = adc1_config.enable_pin(analog_pin, -//! Attenuation::Attenuation11dB); -//! let mut adc1 = Adc::new(peripherals.ADC1, adc1_config); +//! let mut pin = adc1_config.enable_pin( +//! analog_pin, +//! Attenuation::Attenuation11dB, +//! ); +//! let mut adc1 = Adc::new(system.peripherals.ADC1, adc1_config); //! -//! let mut delay = Delay::new(&clocks); +//! let mut delay = Delay::new(&system.clocks); //! //! loop { //! let pin_value: u16 = nb::block!(adc1.read_oneshot(&mut pin)).unwrap(); @@ -54,8 +55,10 @@ //! } //! # } //! ``` +//! //! ## Implementation State -//! - [ADC calibration is not implemented for all targets]. +//! +//! - [ADC calibration is not implemented for all targets]. //! //! [ADC calibration is not implemented for all targets]: https://github.com/esp-rs/esp-hal/issues/326 use core::marker::PhantomData; diff --git a/esp-hal/src/clock/mod.rs b/esp-hal/src/clock/mod.rs index 48a00279354..2ac5d237ae9 100644 --- a/esp-hal/src/clock/mod.rs +++ b/esp-hal/src/clock/mod.rs @@ -13,20 +13,14 @@ //! module clocks. //! //! ## Configuration -//! Proper clock configuration is essential for the correct functioning of the -//! microcontroller and its peripherals. //! -//! The `Clock` driver supports configuring multiple clocks, including: -//! * CPU clock -//! * APB (Advanced Peripheral Bus) clock -//! * XTAL (External Crystal) clock -//! * PLL (Phase Lock Loop) clock -//! -//! and other specific clocks based on the ESP microcontroller's architecture. +//! During HAL initialization, specify a CPU clock speed to configure the +//! desired clock frequencies. //! //! The `CPU clock` is responsible for defining the speed at which the central //! processing unit (CPU) operates. This driver provides predefined options for -//! different CPU clock speeds, such +//! different CPU clock speeds, such as +//! //! * 80 MHz //! * 96 MHz //! * 120 MHz @@ -35,52 +29,48 @@ //! //! and others, depending on the microcontroller model. //! -//! ### Clock Control -//! The `ClockControl` struct allows users to configure the desired clock -//! frequencies before applying them. It offers flexibility in selecting -//! appropriate clock frequencies based on specific application requirements. -//! //! ### Frozen Clock Frequencies -//! Once the clock configuration is applied using the `freeze` function of the -//! ClockControl struct, the clock frequencies become `frozen` and cannot be -//! changed. The `Clocks` struct is returned after freezing, providing read-only -//! access to the configured clock frequencies. +//! +//! Once the clock configuration is applied, the clock frequencies become +//! `frozen` and cannot be changed. The `Clocks` struct is returned as part of +//! the `System` struct, providing read-only access to the configured clock +//! frequencies. //! //! ## Examples +//! //! ### Initialize With Different Clock Frequencies //! ```rust, no_run //! # #![no_std] -//! # use esp_hal::peripherals::Peripherals; -//! # use esp_hal::clock::ClockControl; -//! # use esp_hal::system::SystemControl; +//! # use esp_hal::prelude::*; //! # #[panic_handler] //! # fn panic(_ : &core::panic::PanicInfo) -> ! { //! # loop {} //! # } //! # fn main() { -//! # let peripherals = Peripherals::take(); -//! # let system = SystemControl::new(peripherals.SYSTEM); //! // Initialize with the highest possible frequency for this chip -//! let clocks = ClockControl::max(system.clock_control).freeze(); +//! let system = esp_hal::init(CpuClock::max()); //! //! // Initialize with custom clock frequency -//! // let clocks = ClockControl::configure(system.clock_control, CpuClock::Clock160MHz).freeze(); +#![cfg_attr( + not(any(esp32c2, esp32h2)), + doc = "// let system = esp_hal::init(CpuClock::Clock160MHz);" +)] +#![cfg_attr(esp32c2, doc = "// let system = esp_hal::init(CpuClock::Clock120MHz);")] +#![cfg_attr(esp32h2, doc = "// let system = esp_hal::init(CpuClock::Clock96MHz);")] //! // //! // Initialize with default clock frequency for this chip -//! // let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); +//! // let system = esp_hal::init(CpuClock::boot_default()); //! # } //! ``` +use core::marker::PhantomData; + use fugit::HertzU32; #[cfg(esp32c2)] use portable_atomic::{AtomicU32, Ordering}; #[cfg(any(esp32, esp32c2))] use crate::rtc_cntl::RtcClock; -use crate::{ - peripheral::{Peripheral, PeripheralRef}, - system::SystemClockControl, -}; #[cfg_attr(esp32, path = "clocks_ll/esp32.rs")] #[cfg_attr(esp32c2, path = "clocks_ll/esp32c2.rs")] @@ -108,40 +98,68 @@ pub trait Clock { } /// CPU clock speed -#[derive(Debug, Clone, Copy)] +#[derive(Debug, Clone, Copy, PartialEq, Eq)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] pub enum CpuClock { /// 80MHz CPU clock #[cfg(not(esp32h2))] - Clock80MHz, + Clock80MHz = 80, + /// 96MHz CPU clock #[cfg(esp32h2)] - Clock96MHz, + Clock96MHz = 96, + /// 120MHz CPU clock #[cfg(esp32c2)] - Clock120MHz, + Clock120MHz = 120, + /// 160MHz CPU clock #[cfg(not(any(esp32c2, esp32h2)))] - Clock160MHz, + Clock160MHz = 160, + /// 240MHz CPU clock #[cfg(xtensa)] - Clock240MHz, + Clock240MHz = 240, +} + +impl Default for CpuClock { + fn default() -> Self { + Self::boot_default() + } +} + +impl CpuClock { + /// Use the default frequency. + pub fn boot_default() -> Self { + cfg_if::cfg_if! { + if #[cfg(esp32h2)] { + Self::Clock96MHz + } else { + // FIXME: I don't think this is correct in general? + Self::Clock80MHz + } + } + } + + /// Use the highest possible frequency for a particular chip. + pub fn max() -> Self { + cfg_if::cfg_if! { + if #[cfg(esp32c2)] { + Self::Clock120MHz + } else if #[cfg(any(esp32c3, esp32c6))] { + Self::Clock160MHz + } else if #[cfg(esp32h2)] { + Self::Clock96MHz + } else { + Self::Clock240MHz + } + } + } } -#[allow(dead_code)] impl Clock for CpuClock { fn frequency(&self) -> HertzU32 { - match self { - #[cfg(not(esp32h2))] - CpuClock::Clock80MHz => HertzU32::MHz(80), - #[cfg(esp32h2)] - CpuClock::Clock96MHz => HertzU32::MHz(96), - #[cfg(esp32c2)] - CpuClock::Clock120MHz => HertzU32::MHz(120), - #[cfg(not(any(esp32c2, esp32h2)))] - CpuClock::Clock160MHz => HertzU32::MHz(160), - #[cfg(xtensa)] - CpuClock::Clock240MHz => HertzU32::MHz(240), - } + HertzU32::MHz(*self as u32) } } @@ -257,81 +275,65 @@ impl Clock for ApbClock { /// Frozen clock frequencies /// /// The instantiation of this type indicates that the clock configuration can no -/// longer be changed -pub struct Clocks<'d> { - _private: PeripheralRef<'d, SystemClockControl>, - /// CPU clock frequency - pub cpu_clock: HertzU32, - /// APB clock frequency - pub apb_clock: HertzU32, - /// XTAL clock frequency - pub xtal_clock: HertzU32, - /// I2C clock frequency - #[cfg(esp32)] - pub i2c_clock: HertzU32, - /// PWM clock frequency - #[cfg(esp32)] - pub pwm_clock: HertzU32, - /// Crypto PWM clock frequency - #[cfg(esp32s3)] - pub crypto_pwm_clock: HertzU32, - /// Crypto clock frequency - #[cfg(any(esp32c6, esp32h2))] - pub crypto_clock: HertzU32, - /// PLL 48M clock frequency (fixed) - #[cfg(esp32h2)] - pub pll_48m_clock: HertzU32, - /// PLL 96M clock frequency (fixed) - #[cfg(esp32h2)] - pub pll_96m_clock: HertzU32, +/// longer be changed. +pub struct Clocks<'a> { + _private: PhantomData<&'a ()>, + rates: RawClocks, } -#[doc(hidden)] -impl<'d> Clocks<'d> { +impl<'a> Clocks<'a> { /// This should not be used in user code. /// The whole point this exists is make it possible to have other crates /// (i.e. esp-wifi) create `Clocks` #[doc(hidden)] - pub fn from_raw_clocks( - system_clock_control: PeripheralRef<'d, SystemClockControl>, - raw_clocks: RawClocks, - ) -> Clocks<'d> { + pub(crate) fn from_raw_clocks(raw_clocks: RawClocks) -> Clocks<'a> { Self { - _private: system_clock_control, - cpu_clock: raw_clocks.cpu_clock, - apb_clock: raw_clocks.apb_clock, - xtal_clock: raw_clocks.xtal_clock, - #[cfg(esp32)] - i2c_clock: raw_clocks.i2c_clock, - #[cfg(esp32)] - pwm_clock: raw_clocks.pwm_clock, - #[cfg(esp32s3)] - crypto_pwm_clock: raw_clocks.crypto_pwm_clock, - #[cfg(any(esp32c6, esp32h2))] - crypto_clock: raw_clocks.crypto_clock, - #[cfg(esp32h2)] - pll_48m_clock: raw_clocks.pll_48m_clock, - #[cfg(esp32h2)] - pll_96m_clock: raw_clocks.pll_96m_clock, + _private: PhantomData, + rates: raw_clocks, } } } -#[doc(hidden)] +impl core::ops::Deref for Clocks<'_> { + type Target = RawClocks; + + fn deref(&self) -> &RawClocks { + &self.rates + } +} + +/// The list of the clock frequencies that are used in the system. pub struct RawClocks { + /// CPU clock frequency pub cpu_clock: HertzU32, + + /// APB clock frequency pub apb_clock: HertzU32, + + /// XTAL clock frequency pub xtal_clock: HertzU32, + + /// I2C clock frequency #[cfg(esp32)] pub i2c_clock: HertzU32, + + /// PWM clock frequency #[cfg(esp32)] pub pwm_clock: HertzU32, + + /// Crypto PWM clock frequency #[cfg(esp32s3)] pub crypto_pwm_clock: HertzU32, + + /// Crypto clock frequency #[cfg(any(esp32c6, esp32h2))] pub crypto_clock: HertzU32, + + /// PLL 48M clock frequency (fixed) #[cfg(esp32h2)] pub pll_48m_clock: HertzU32, + + /// PLL 96M clock frequency (fixed) #[cfg(esp32h2)] pub pll_96m_clock: HertzU32, } @@ -360,72 +362,51 @@ cfg_if::cfg_if! { /// /// After setting all frequencies, call the freeze function to apply the /// configuration. -pub struct ClockControl<'d> { - _private: PeripheralRef<'d, SystemClockControl>, +pub struct ClockControl { desired_rates: RawClocks, } -impl<'d> ClockControl<'d> { +impl ClockControl { + pub(crate) fn new(clock: CpuClock) -> Self { + Self::configure(clock) + } + /// Applies the clock configuration and returns a Clocks struct that /// signifies that the clocks are frozen, and contains the frequencies /// used. After this function is called, the clocks can not change - pub fn freeze(self) -> Clocks<'d> { - Clocks::from_raw_clocks(self._private, self.desired_rates) + pub fn freeze(self) -> Clocks<'static> { + Clocks::from_raw_clocks(self.desired_rates) } } #[cfg(esp32)] -impl<'d> ClockControl<'d> { - /// Use what is considered the default settings after boot. - pub fn boot_defaults( - clock_control: impl Peripheral

+ 'd, - ) -> ClockControl<'d> { - let xtal_freq = if RtcClock::estimate_xtal_frequency() > 33 { - 40 - } else { - 26 - }; - - ClockControl { - _private: clock_control.into_ref(), - desired_rates: RawClocks { - cpu_clock: HertzU32::MHz(80), - apb_clock: HertzU32::MHz(80), - xtal_clock: HertzU32::MHz(xtal_freq), - i2c_clock: HertzU32::MHz(80), - pwm_clock: HertzU32::MHz(160), - }, - } - } - +impl ClockControl { /// Configure the CPU clock speed. - pub fn configure( - clock_control: impl Peripheral

+ 'd, - cpu_clock_speed: CpuClock, - ) -> ClockControl<'d> { + pub(crate) fn configure(cpu_clock_speed: CpuClock) -> ClockControl { let xtal_freq = if RtcClock::estimate_xtal_frequency() > 33 { XtalClock::RtcXtalFreq40M } else { XtalClock::RtcXtalFreq26M }; - let pll_freq = match cpu_clock_speed { - CpuClock::Clock80MHz => PllClock::Pll320MHz, - CpuClock::Clock160MHz => PllClock::Pll320MHz, - CpuClock::Clock240MHz => PllClock::Pll480MHz, - }; - - clocks_ll::esp32_rtc_update_to_xtal(xtal_freq, 1); - clocks_ll::esp32_rtc_bbpll_enable(); - clocks_ll::esp32_rtc_bbpll_configure(xtal_freq, pll_freq); - clocks_ll::set_cpu_freq(cpu_clock_speed); + if cpu_clock_speed != CpuClock::boot_default() { + let pll_freq = match cpu_clock_speed { + CpuClock::Clock80MHz => PllClock::Pll320MHz, + CpuClock::Clock160MHz => PllClock::Pll320MHz, + CpuClock::Clock240MHz => PllClock::Pll480MHz, + }; + + clocks_ll::esp32_rtc_update_to_xtal(xtal_freq, 1); + clocks_ll::esp32_rtc_bbpll_enable(); + clocks_ll::esp32_rtc_bbpll_configure(xtal_freq, pll_freq); + clocks_ll::set_cpu_freq(cpu_clock_speed); + } ClockControl { - _private: clock_control.into_ref(), desired_rates: RawClocks { cpu_clock: cpu_clock_speed.frequency(), apb_clock: HertzU32::MHz(80), - xtal_clock: HertzU32::MHz(40), + xtal_clock: HertzU32::MHz(xtal_freq.mhz()), i2c_clock: HertzU32::MHz(80), // The docs are unclear here. pwm_clock seems to be tied to clocks.apb_clock // while simultaneously being fixed at 160 MHz. @@ -434,43 +415,12 @@ impl<'d> ClockControl<'d> { }, } } - - /// Use the highest possible frequency for a particular chip - pub fn max(clock_control: impl Peripheral

+ 'd) -> ClockControl<'d> { - Self::configure(clock_control, CpuClock::Clock240MHz) - } } #[cfg(esp32c2)] -impl<'d> ClockControl<'d> { - /// Use what is considered the default settings after boot. - pub fn boot_defaults( - clock_control: impl Peripheral

+ 'd, - ) -> ClockControl<'d> { - let xtal_freq = if RtcClock::estimate_xtal_frequency() > 33 { - 40 - } else { - 26 - }; - XTAL_FREQ_MHZ.store(xtal_freq, Ordering::Relaxed); - - ClockControl { - _private: clock_control.into_ref(), - desired_rates: RawClocks { - cpu_clock: HertzU32::MHz(80), - apb_clock: HertzU32::MHz(40), - xtal_clock: HertzU32::MHz(xtal_freq), - }, - } - } - +impl ClockControl { /// Configure the CPU clock speed. - pub fn configure( - clock_control: impl Peripheral

+ 'd, - cpu_clock_speed: CpuClock, - ) -> ClockControl<'d> { - let apb_freq; - + pub(crate) fn configure(cpu_clock_speed: CpuClock) -> ClockControl { let xtal_freq = if RtcClock::estimate_xtal_frequency() > 33 { XtalClock::RtcXtalFreq40M } else { @@ -478,22 +428,26 @@ impl<'d> ClockControl<'d> { }; XTAL_FREQ_MHZ.store(xtal_freq.mhz(), Ordering::Relaxed); - let pll_freq = PllClock::Pll480MHz; - - if cpu_clock_speed.mhz() <= xtal_freq.mhz() { - apb_freq = ApbClock::ApbFreqOther(cpu_clock_speed.mhz()); - clocks_ll::esp32c2_rtc_update_to_xtal(xtal_freq, 1); - clocks_ll::esp32c2_rtc_apb_freq_update(apb_freq); + let apb_freq; + if cpu_clock_speed != CpuClock::boot_default() { + let pll_freq = PllClock::Pll480MHz; + + if cpu_clock_speed.mhz() <= xtal_freq.mhz() { + apb_freq = ApbClock::ApbFreqOther(cpu_clock_speed.mhz()); + clocks_ll::esp32c2_rtc_update_to_xtal(xtal_freq, 1); + clocks_ll::esp32c2_rtc_apb_freq_update(apb_freq); + } else { + apb_freq = ApbClock::ApbFreq40MHz; + clocks_ll::esp32c2_rtc_bbpll_enable(); + clocks_ll::esp32c2_rtc_bbpll_configure(xtal_freq, pll_freq); + clocks_ll::esp32c2_rtc_freq_to_pll_mhz(cpu_clock_speed); + clocks_ll::esp32c2_rtc_apb_freq_update(apb_freq); + } } else { apb_freq = ApbClock::ApbFreq40MHz; - clocks_ll::esp32c2_rtc_bbpll_enable(); - clocks_ll::esp32c2_rtc_bbpll_configure(xtal_freq, pll_freq); - clocks_ll::esp32c2_rtc_freq_to_pll_mhz(cpu_clock_speed); - clocks_ll::esp32c2_rtc_apb_freq_update(apb_freq); } ClockControl { - _private: clock_control.into_ref(), desired_rates: RawClocks { cpu_clock: cpu_clock_speed.frequency(), apb_clock: apb_freq.frequency(), @@ -501,52 +455,33 @@ impl<'d> ClockControl<'d> { }, } } - - /// Use the highest possible frequency for a particular chip - pub fn max(clock_control: impl Peripheral

+ 'd) -> ClockControl<'d> { - Self::configure(clock_control, CpuClock::Clock120MHz) - } } #[cfg(esp32c3)] -impl<'d> ClockControl<'d> { - /// Use what is considered the default settings after boot. - pub fn boot_defaults( - clock_control: impl Peripheral

+ 'd, - ) -> ClockControl<'d> { - ClockControl { - _private: clock_control.into_ref(), - desired_rates: RawClocks { - cpu_clock: HertzU32::MHz(80), - apb_clock: HertzU32::MHz(80), - xtal_clock: HertzU32::MHz(40), - }, - } - } - +impl ClockControl { /// Configure the CPU clock speed. - pub fn configure( - clock_control: impl Peripheral

+ 'd, - cpu_clock_speed: CpuClock, - ) -> ClockControl<'d> { - let apb_freq; + pub(crate) fn configure(cpu_clock_speed: CpuClock) -> ClockControl { let xtal_freq = XtalClock::RtcXtalFreq40M; - let pll_freq = PllClock::Pll480MHz; - if cpu_clock_speed.mhz() <= xtal_freq.mhz() { - apb_freq = ApbClock::ApbFreqOther(cpu_clock_speed.mhz()); - clocks_ll::esp32c3_rtc_update_to_xtal(xtal_freq, 1); - clocks_ll::esp32c3_rtc_apb_freq_update(apb_freq); + let apb_freq; + if cpu_clock_speed != CpuClock::boot_default() { + if cpu_clock_speed.mhz() <= xtal_freq.mhz() { + apb_freq = ApbClock::ApbFreqOther(cpu_clock_speed.mhz()); + clocks_ll::esp32c3_rtc_update_to_xtal(xtal_freq, 1); + clocks_ll::esp32c3_rtc_apb_freq_update(apb_freq); + } else { + let pll_freq = PllClock::Pll480MHz; + apb_freq = ApbClock::ApbFreq80MHz; + clocks_ll::esp32c3_rtc_bbpll_enable(); + clocks_ll::esp32c3_rtc_bbpll_configure(xtal_freq, pll_freq); + clocks_ll::esp32c3_rtc_freq_to_pll_mhz(cpu_clock_speed); + clocks_ll::esp32c3_rtc_apb_freq_update(apb_freq); + } } else { apb_freq = ApbClock::ApbFreq80MHz; - clocks_ll::esp32c3_rtc_bbpll_enable(); - clocks_ll::esp32c3_rtc_bbpll_configure(xtal_freq, pll_freq); - clocks_ll::esp32c3_rtc_freq_to_pll_mhz(cpu_clock_speed); - clocks_ll::esp32c3_rtc_apb_freq_update(apb_freq); } ClockControl { - _private: clock_control.into_ref(), desired_rates: RawClocks { cpu_clock: cpu_clock_speed.frequency(), apb_clock: apb_freq.frequency(), @@ -554,53 +489,33 @@ impl<'d> ClockControl<'d> { }, } } - - /// Use the highest possible frequency for a particular chip - pub fn max(clock_control: impl Peripheral

+ 'd) -> ClockControl<'d> { - Self::configure(clock_control, CpuClock::Clock160MHz) - } } #[cfg(esp32c6)] -impl<'d> ClockControl<'d> { - /// Use what is considered the default settings after boot. - pub fn boot_defaults( - clock_control: impl Peripheral

+ 'd, - ) -> ClockControl<'d> { - ClockControl { - _private: clock_control.into_ref(), - desired_rates: RawClocks { - cpu_clock: HertzU32::MHz(80), - apb_clock: HertzU32::MHz(80), - xtal_clock: HertzU32::MHz(40), - crypto_clock: HertzU32::MHz(160), - }, - } - } - +impl ClockControl { /// Configure the CPU clock speed. - pub fn configure( - clock_control: impl Peripheral

+ 'd, - cpu_clock_speed: CpuClock, - ) -> ClockControl<'d> { - let apb_freq; + pub(crate) fn configure(cpu_clock_speed: CpuClock) -> ClockControl { let xtal_freq = XtalClock::RtcXtalFreq40M; - let pll_freq = PllClock::Pll480MHz; - if cpu_clock_speed.mhz() <= xtal_freq.mhz() { - apb_freq = ApbClock::ApbFreqOther(cpu_clock_speed.mhz()); - clocks_ll::esp32c6_rtc_update_to_xtal(xtal_freq, 1); - clocks_ll::esp32c6_rtc_apb_freq_update(apb_freq); + let apb_freq; + if cpu_clock_speed != CpuClock::boot_default() { + if cpu_clock_speed.mhz() <= xtal_freq.mhz() { + apb_freq = ApbClock::ApbFreqOther(cpu_clock_speed.mhz()); + clocks_ll::esp32c6_rtc_update_to_xtal(xtal_freq, 1); + clocks_ll::esp32c6_rtc_apb_freq_update(apb_freq); + } else { + let pll_freq = PllClock::Pll480MHz; + apb_freq = ApbClock::ApbFreq80MHz; + clocks_ll::esp32c6_rtc_bbpll_enable(); + clocks_ll::esp32c6_rtc_bbpll_configure(xtal_freq, pll_freq); + clocks_ll::esp32c6_rtc_freq_to_pll_mhz(cpu_clock_speed); + clocks_ll::esp32c6_rtc_apb_freq_update(apb_freq); + } } else { apb_freq = ApbClock::ApbFreq80MHz; - clocks_ll::esp32c6_rtc_bbpll_enable(); - clocks_ll::esp32c6_rtc_bbpll_configure(xtal_freq, pll_freq); - clocks_ll::esp32c6_rtc_freq_to_pll_mhz(cpu_clock_speed); - clocks_ll::esp32c6_rtc_apb_freq_update(apb_freq); } ClockControl { - _private: clock_control.into_ref(), desired_rates: RawClocks { cpu_clock: cpu_clock_speed.frequency(), apb_clock: apb_freq.frequency(), @@ -609,55 +524,33 @@ impl<'d> ClockControl<'d> { }, } } - - /// Use the highest possible frequency for a particular chip - pub fn max(clock_control: impl Peripheral

+ 'd) -> ClockControl<'d> { - Self::configure(clock_control, CpuClock::Clock160MHz) - } } #[cfg(esp32h2)] -impl<'d> ClockControl<'d> { - /// Use what is considered the default settings after boot. - pub fn boot_defaults( - clock_control: impl Peripheral

+ 'd, - ) -> ClockControl<'d> { - ClockControl { - _private: clock_control.into_ref(), - desired_rates: RawClocks { - cpu_clock: HertzU32::MHz(96), - apb_clock: HertzU32::MHz(32), - xtal_clock: HertzU32::MHz(32), - pll_48m_clock: HertzU32::MHz(48), - crypto_clock: HertzU32::MHz(96), - pll_96m_clock: HertzU32::MHz(96), - }, - } - } - +impl ClockControl { /// Configure the CPU clock speed. - pub fn configure( - clock_control: impl Peripheral

+ 'd, - cpu_clock_speed: CpuClock, - ) -> ClockControl<'d> { - let apb_freq; + pub(crate) fn configure(cpu_clock_speed: CpuClock) -> ClockControl { let xtal_freq = XtalClock::RtcXtalFreq32M; - let pll_freq = PllClock::Pll96MHz; - if cpu_clock_speed.mhz() <= xtal_freq.mhz() { - apb_freq = ApbClock::ApbFreqOther(cpu_clock_speed.mhz()); - clocks_ll::esp32h2_rtc_update_to_xtal(xtal_freq, 1); - clocks_ll::esp32h2_rtc_apb_freq_update(apb_freq); + let apb_freq; + if cpu_clock_speed != CpuClock::boot_default() { + if cpu_clock_speed.mhz() <= xtal_freq.mhz() { + apb_freq = ApbClock::ApbFreqOther(cpu_clock_speed.mhz()); + clocks_ll::esp32h2_rtc_update_to_xtal(xtal_freq, 1); + clocks_ll::esp32h2_rtc_apb_freq_update(apb_freq); + } else { + let pll_freq = PllClock::Pll96MHz; + apb_freq = ApbClock::ApbFreq32MHz; + clocks_ll::esp32h2_rtc_bbpll_enable(); + clocks_ll::esp32h2_rtc_bbpll_configure(xtal_freq, pll_freq); + clocks_ll::esp32h2_rtc_freq_to_pll_mhz(cpu_clock_speed); + clocks_ll::esp32h2_rtc_apb_freq_update(apb_freq); + } } else { apb_freq = ApbClock::ApbFreq32MHz; - clocks_ll::esp32h2_rtc_bbpll_enable(); - clocks_ll::esp32h2_rtc_bbpll_configure(xtal_freq, pll_freq); - clocks_ll::esp32h2_rtc_freq_to_pll_mhz(cpu_clock_speed); - clocks_ll::esp32h2_rtc_apb_freq_update(apb_freq); } ClockControl { - _private: clock_control.into_ref(), desired_rates: RawClocks { cpu_clock: cpu_clock_speed.frequency(), apb_clock: apb_freq.frequency(), @@ -668,38 +561,17 @@ impl<'d> ClockControl<'d> { }, } } - - /// Use the highest possible frequency for a particular chip - pub fn max(clock_control: impl Peripheral

+ 'd) -> ClockControl<'d> { - Self::configure(clock_control, CpuClock::Clock96MHz) - } } #[cfg(esp32s2)] -impl<'d> ClockControl<'d> { - /// Use what is considered the default settings after boot. - pub fn boot_defaults( - clock_control: impl Peripheral

+ 'd, - ) -> ClockControl<'d> { - ClockControl { - _private: clock_control.into_ref(), - desired_rates: RawClocks { - cpu_clock: HertzU32::MHz(80), - apb_clock: HertzU32::MHz(80), - xtal_clock: HertzU32::MHz(40), - }, - } - } - +impl ClockControl { /// Configure the CPU clock speed. - pub fn configure( - clock_control: impl Peripheral

+ 'd, - cpu_clock_speed: CpuClock, - ) -> ClockControl<'d> { - clocks_ll::set_cpu_clock(cpu_clock_speed); + pub(crate) fn configure(cpu_clock_speed: CpuClock) -> ClockControl { + if cpu_clock_speed != CpuClock::boot_default() { + clocks_ll::set_cpu_clock(cpu_clock_speed); + } ClockControl { - _private: clock_control.into_ref(), desired_rates: RawClocks { cpu_clock: cpu_clock_speed.frequency(), apb_clock: HertzU32::MHz(80), @@ -707,39 +579,17 @@ impl<'d> ClockControl<'d> { }, } } - - /// Use the highest possible frequency for a particular chip - pub fn max(clock_control: impl Peripheral

+ 'd) -> ClockControl<'d> { - Self::configure(clock_control, CpuClock::Clock240MHz) - } } #[cfg(esp32s3)] -impl<'d> ClockControl<'d> { - /// Use what is considered the default settings after boot. - pub fn boot_defaults( - clock_control: impl Peripheral

+ 'd, - ) -> ClockControl<'d> { - ClockControl { - _private: clock_control.into_ref(), - desired_rates: RawClocks { - cpu_clock: HertzU32::MHz(80), - apb_clock: HertzU32::MHz(80), - xtal_clock: HertzU32::MHz(40), - crypto_pwm_clock: HertzU32::MHz(160), - }, - } - } - +impl ClockControl { /// Configure the CPU clock speed. - pub fn configure( - clock_control: impl Peripheral

+ 'd, - cpu_clock_speed: CpuClock, - ) -> ClockControl<'d> { - clocks_ll::set_cpu_clock(cpu_clock_speed); + pub(crate) fn configure(cpu_clock_speed: CpuClock) -> ClockControl { + if cpu_clock_speed != CpuClock::boot_default() { + clocks_ll::set_cpu_clock(cpu_clock_speed); + } ClockControl { - _private: clock_control.into_ref(), desired_rates: RawClocks { cpu_clock: cpu_clock_speed.frequency(), apb_clock: HertzU32::MHz(80), @@ -748,9 +598,4 @@ impl<'d> ClockControl<'d> { }, } } - - /// Use the highest possible frequency for a particular chip - pub fn max(clock_control: impl Peripheral

+ 'd) -> ClockControl<'d> { - Self::configure(clock_control, CpuClock::Clock240MHz) - } } diff --git a/esp-hal/src/delay.rs b/esp-hal/src/delay.rs index 842d7bcbf28..a43aedb6629 100644 --- a/esp-hal/src/delay.rs +++ b/esp-hal/src/delay.rs @@ -1,16 +1,18 @@ //! # Delay //! //! ## Overview +//! //! The Delay driver provides blocking delay functionalities using the -//! `SYSTIMER` peripheral for RISC-V devices and the built-in Xtensa timer for -//! Xtensa devices. +//! [current_time] function. //! //! ## Configuration +//! //! The delays are implemented in a "best-effort" way, meaning that the CPU will //! block for at least the amount of time specified, but accuracy can be //! affected by many factors, including interrupt usage. //! //! ## Usage +//! //! This module implements the blocking [DelayMs] and [DelayUs] traits from //! [embedded-hal], both 0.2.x and 1.x.x. //! @@ -20,7 +22,9 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::delay::Delay; //! # use embedded_hal::delay::DelayNs; -//! let mut delay = Delay::new(&clocks); +//! let system = esp_hal::init(CpuClock::boot_default()); +//! +//! let mut delay = Delay::new(&system.clocks); //! //! delay.delay_ms(1000 as u32); //! # } diff --git a/esp-hal/src/dma/mod.rs b/esp-hal/src/dma/mod.rs index 5dc5e2ec48b..22b14f7cf3c 100644 --- a/esp-hal/src/dma/mod.rs +++ b/esp-hal/src/dma/mod.rs @@ -21,17 +21,22 @@ //! # use esp_hal::gpio::Io; //! # use esp_hal::spi::{master::Spi, SpiMode}; //! # use esp_hal::dma::{Dma, DmaPriority}; -//! # use crate::esp_hal::prelude::_fugit_RateExtU32; -//! let dma = Dma::new(peripherals.DMA); +//! let system = esp_hal::init(CpuClock::boot_default()); +//! let dma = Dma::new(system.peripherals.DMA); #![cfg_attr(any(esp32, esp32s2), doc = "let dma_channel = dma.spi2channel;")] #![cfg_attr(not(any(esp32, esp32s2)), doc = "let dma_channel = dma.channel0;")] -//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); //! let sclk = io.pins.gpio0; //! let miso = io.pins.gpio2; //! let mosi = io.pins.gpio4; //! let cs = io.pins.gpio5; //! -//! let mut spi = Spi::new(peripherals.SPI2, 100.kHz(), SpiMode::Mode0, &clocks) +//! let mut spi = Spi::new( +//! system.peripherals.SPI2, +//! 100.kHz(), +//! SpiMode::Mode0, +//! &system.clocks +//! ) //! .with_pins(Some(sclk), Some(mosi), Some(miso), Some(cs)) //! .with_dma(dma_channel.configure( //! false, @@ -43,10 +48,10 @@ //! ⚠️ Note: Descriptors should be sized as `(max_transfer_size + CHUNK_SIZE - 1) / CHUNK_SIZE`. //! I.e., to transfer buffers of size `1..=CHUNK_SIZE`, you need 1 descriptor. //! -//! ⚠️ Note: For chips that support DMA to/from PSRAM (esp32s3) DMA transfers to/from PSRAM +//! ⚠️ Note: For chips that support DMA to/from PSRAM (ESP32-S3) DMA transfers to/from PSRAM //! have extra alignment requirements. The address and size of the buffer pointed to by //! each descriptor must be a multiple of the cache line (block) size. This is 32 bytes -//! on esp32s3. +//! on ESP32-S3. //! //! For convenience you can use the [crate::dma_buffers] macro. @@ -288,7 +293,7 @@ mod gdma; #[cfg(pdma)] mod pdma; -/// Kinds of interrupt to listen to +/// Kinds of interrupt to listen to. #[derive(EnumSetType)] pub enum DmaInterrupt { /// TX is done @@ -297,15 +302,21 @@ pub enum DmaInterrupt { RxDone, } -/// The default CHUNK_SIZE used for DMA transfers +/// The default chunk size used for DMA transfers. pub const CHUNK_SIZE: usize = 4092; -/// Convenience macro to create DMA buffers and descriptors +/// Convenience macro to create DMA buffers and descriptors. /// /// ## Usage -/// ```rust,ignore -/// // TX and RX buffers are 32000 bytes - passing only one parameter makes TX and RX the same size -/// let (tx_buffer, tx_descriptors, rx_buffer, rx_descriptors) = dma_buffers!(32000, 32000); +/// ```rust,no_run +#[doc = crate::before_snippet!()] +/// use esp_hal::dma_buffers; +/// +/// // TX and RX buffers are 32000 bytes - passing only one parameter makes TX +/// // and RX the same size. +/// let (tx_buffer, tx_descriptors, rx_buffer, rx_descriptors) = +/// dma_buffers!(32000, 32000); +/// # } /// ``` #[macro_export] macro_rules! dma_buffers { @@ -317,13 +328,18 @@ macro_rules! dma_buffers { }; } -/// Convenience macro to create circular DMA buffers and descriptors +/// Convenience macro to create circular DMA buffers and descriptors. /// /// ## Usage -/// ```rust,ignore -/// // TX and RX buffers are 32000 bytes - passing only one parameter makes TX and RX the same size +/// ```rust,no_run +#[doc = crate::before_snippet!()] +/// use esp_hal::dma_circular_buffers; +/// +/// // TX and RX buffers are 32000 bytes - passing only one parameter makes TX +/// // and RX the same size. /// let (tx_buffer, tx_descriptors, rx_buffer, rx_descriptors) = /// dma_circular_buffers!(32000, 32000); +/// # } /// ``` #[macro_export] macro_rules! dma_circular_buffers { @@ -336,12 +352,17 @@ macro_rules! dma_circular_buffers { }; } -/// Convenience macro to create DMA descriptors +/// Convenience macro to create DMA descriptors. /// /// ## Usage -/// ```rust,ignore -/// // Create TX and RX descriptors for transactions up to 32000 bytes - passing only one parameter assumes TX and RX are the same size +/// ```rust,no_run +#[doc = crate::before_snippet!()] +/// use esp_hal::dma_descriptors; +/// +/// // Create TX and RX descriptors for transactions up to 32000 bytes - passing +/// // only one parameter assumes TX and RX are the same size. /// let (tx_descriptors, rx_descriptors) = dma_descriptors!(32000, 32000); +/// # } /// ``` #[macro_export] macro_rules! dma_descriptors { @@ -354,12 +375,18 @@ macro_rules! dma_descriptors { }; } -/// Convenience macro to create circular DMA descriptors +/// Convenience macro to create circular DMA descriptors. /// /// ## Usage -/// ```rust,ignore -/// // Create TX and RX descriptors for transactions up to 32000 bytes - passing only one parameter assumes TX and RX are the same size -/// let (tx_descriptors, rx_descriptors) = dma_circular_descriptors!(32000, 32000); +/// ```rust,no_run +#[doc = crate::before_snippet!()] +/// use esp_hal::dma_circular_descriptors; +/// +/// // Create TX and RX descriptors for transactions up to 32000 +/// // bytes - passing only one parameter assumes TX and RX are the same size. +/// let (tx_descriptors, rx_descriptors) = +/// dma_circular_descriptors!(32000, 32000); +/// # } /// ``` #[macro_export] macro_rules! dma_circular_descriptors { @@ -373,12 +400,18 @@ macro_rules! dma_circular_descriptors { } /// Convenience macro to create DMA buffers and descriptors with specific chunk -/// size +/// size. /// /// ## Usage -/// ```rust,ignore -/// // TX and RX buffers are 32000 bytes - passing only one parameter makes TX and RX the same size -/// let (tx_buffer, tx_descriptors, rx_buffer, rx_descriptors) = dma_buffers!(32000, 32000, 4032); +/// ```rust,no_run +#[doc = crate::before_snippet!()] +/// use esp_hal::dma_buffers_chunk_size; +/// +/// // TX and RX buffers are 32000 bytes - passing only one parameter makes TX +/// // and RX the same size. +/// let (tx_buffer, tx_descriptors, rx_buffer, rx_descriptors) = +/// dma_buffers_chunk_size!(32000, 32000, 4032); +/// # } /// ``` #[macro_export] macro_rules! dma_buffers_chunk_size { @@ -403,13 +436,18 @@ macro_rules! dma_buffers_chunk_size { } /// Convenience macro to create circular DMA buffers and descriptors with -/// specific chunk size +/// specific chunk size. /// /// ## Usage -/// ```rust,ignore -/// // TX and RX buffers are 32000 bytes - passing only one parameter makes TX and RX the same size +/// ```rust,no_run +#[doc = crate::before_snippet!()] +/// use esp_hal::dma_circular_buffers_chunk_size; +/// +/// // TX and RX buffers are 32000 bytes - passing only one parameter makes TX +/// // and RX the same size. /// let (tx_buffer, tx_descriptors, rx_buffer, rx_descriptors) = -/// dma_circular_buffers!(32000, 32000, 4032); +/// dma_circular_buffers_chunk_size!(32000, 32000, 4032); +/// # } /// ``` #[macro_export] macro_rules! dma_circular_buffers_chunk_size { @@ -436,9 +474,15 @@ macro_rules! dma_circular_buffers_chunk_size { /// Convenience macro to create DMA descriptors with specific chunk size /// /// ## Usage -/// ```rust,ignore -/// // Create TX and RX descriptors for transactions up to 32000 bytes - passing only one parameter assumes TX and RX are the same size -/// let (tx_descriptors, rx_descriptors) = dma_descriptors_chunk_size!(32000, 32000, 4032); +/// ```rust,no_run +#[doc = crate::before_snippet!()] +/// use esp_hal::dma_descriptors_chunk_size; +/// +/// // Create TX and RX descriptors for transactions up to 32000 bytes - passing +/// // only one parameter assumes TX and RX are the same size. +/// let (tx_descriptors, rx_descriptors) = +/// dma_descriptors_chunk_size!(32000, 32000, 4032); +/// # } /// ``` #[macro_export] macro_rules! dma_descriptors_chunk_size { @@ -465,9 +509,15 @@ macro_rules! dma_descriptors_chunk_size { /// size /// /// ## Usage -/// ```rust,ignore -/// // Create TX and RX descriptors for transactions up to 32000 bytes - passing only one parameter assumes TX and RX are the same size -/// let (tx_descriptors, rx_descriptors) = dma_circular_descriptors!(32000, 32000, 4032); +/// ```rust,no_run +#[doc = crate::before_snippet!()] +/// use esp_hal::dma_circular_descriptors_chunk_size; +/// +/// // Create TX and RX descriptors for transactions up to 32000 bytes - passing +/// // only one parameter assumes TX and RX are the same size. +/// let (tx_descriptors, rx_descriptors) = +/// dma_circular_descriptors_chunk_size!(32000, 32000, 4032); +/// # } /// ``` #[macro_export] macro_rules! dma_circular_descriptors_chunk_size { diff --git a/esp-hal/src/gpio/mod.rs b/esp-hal/src/gpio/mod.rs index d89deb7ca45..4f29cd20769 100644 --- a/esp-hal/src/gpio/mod.rs +++ b/esp-hal/src/gpio/mod.rs @@ -37,7 +37,8 @@ //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::gpio::{Io, Level, Output}; -//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! let system = esp_hal::init(CpuClock::boot_default()); +//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); //! let mut led = Output::new(io.pins.gpio5, Level::High); //! # } //! ``` diff --git a/esp-hal/src/gpio/rtc_io.rs b/esp-hal/src/gpio/rtc_io.rs index 423e2b9cee6..5e77e7b7191 100644 --- a/esp-hal/src/gpio/rtc_io.rs +++ b/esp-hal/src/gpio/rtc_io.rs @@ -1,10 +1,12 @@ //! RTC IO //! //! # Overview +//! //! The hardware provides a couple of GPIO pins with low power (LP) //! capabilities and analog functions. //! //! ## Configuration +//! //! These pins can be controlled by either IO MUX or RTC IO. //! //! If controlled by RTC IO, these pins will bypass IO MUX and GPIO @@ -14,12 +16,19 @@ //! the peripherals in RTC system during chip Deep-sleep, and wake up the //! chip from Deep-sleep. //! -//! # Example -//! ## Configure a ULP Pin as Output -//! ```rust, ignore -//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! ## Example +//! +//! ### Configure a ULP Pin as Output +//! +//! ```rust, no_run +#![doc = crate::before_snippet!()] +//! # use esp_hal::gpio::rtc_io::LowPowerOutput; +//! # use esp_hal::gpio::Io; +//! let system = esp_hal::init(CpuClock::boot_default()); +//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); //! // configure GPIO 1 as ULP output pin -//! let lp_pin = LowPowerOutput::new(io.pins.gpio1); +//! let lp_pin = LowPowerOutput::<'static, 1>::new(io.pins.gpio1); +//! # } //! ``` use core::marker::PhantomData; diff --git a/esp-hal/src/i2c.rs b/esp-hal/src/i2c.rs index c3071229027..2a54c84c314 100644 --- a/esp-hal/src/i2c.rs +++ b/esp-hal/src/i2c.rs @@ -5,61 +5,46 @@ //! same bus. I2C uses two bidirectional open-drain lines: serial data line //! (SDA) and serial clock line (SCL), pulled up by resistors. //! -//! Espressif devices sometimes have more than one I2C controller (also called -//! port), responsible for handling communication on the I2C bus. A single I2C -//! controller can be a master or a slave. +//! Espressif devices sometimes have more than one I2C controller, responsible +//! for handling communication on the I2C bus. A single I2C controller can be +//! a master or a slave. //! //! Typically, an I2C slave device has a 7-bit address or 10-bit address. -//! Espressif devices supports both I2C Standard-mode (Sm) and Fast-mode -//! (Fm) which can go up to 100KHz and 400KHz respectively. +//! Devices supports both I2C Standard-mode (Sm) and Fast-mode (Fm) which can +//! go up to 100KHz and 400KHz respectively. //! //! ## Configuration //! //! Each I2C controller is individually configurable, and the usual setting //! such as frequency, timeout, and SDA/SCL pins can easily be configured. //! -//! ```rust, no_run -#![doc = crate::before_snippet!()] -//! # use esp_hal::i2c::I2C; -//! # use esp_hal::gpio::Io; -//! # use crate::esp_hal::prelude::_fugit_RateExtU32; -//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); -//! // Create a new peripheral object with the described wiring -//! // and standard I2C clock speed -//! let mut i2c = I2C::new( -//! peripherals.I2C0, -//! io.pins.gpio1, -//! io.pins.gpio2, -//! 100.kHz(), -//! &clocks, -//! ); -//! # } -//! ``` -//! //! ## Usage //! //! The I2C driver implements a number of third-party traits, with the //! intention of making the HAL inter-compatible with various device drivers //! from the community. This includes the [embedded-hal] for both 0.2.x and -//! 1.x.x versions. +//! 1.0.x versions. //! //! ## Examples +//! //! ### Read Data from a BMP180 Sensor +//! //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::i2c::I2C; //! # use esp_hal::gpio::Io; -//! # use crate::esp_hal::prelude::_fugit_RateExtU32; -//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! //! // Create a new peripheral object with the described wiring -//! // and standard I2C clock speed +//! // and standard I2C clock speed. //! let mut i2c = I2C::new( -//! peripherals.I2C0, +//! system.peripherals.I2C0, //! io.pins.gpio1, //! io.pins.gpio2, //! 100.kHz(), -//! &clocks, +//! &system.clocks, //! ); +//! //! loop { //! let mut data = [0u8; 22]; //! i2c.write_read(0x77, &[0xaa], &mut data).ok(); diff --git a/esp-hal/src/i2s.rs b/esp-hal/src/i2s.rs index 08f0f3a5b32..79717993c1b 100644 --- a/esp-hal/src/i2s.rs +++ b/esp-hal/src/i2s.rs @@ -1,14 +1,15 @@ //! # Inter-IC Sound (I2S) //! //! ## Overview +//! //! I2S (Inter-IC Sound) is a synchronous serial communication protocol usually //! used for transmitting audio data between two digital audio devices. //! Espressif devices may contain more than one I2S peripheral(s). These //! peripherals can be configured to input and output sample data via the I2S //! driver. //! -//! //! ## Configuration +//! //! I2S supports different data formats, including varying data and channel //! widths, different standards, such as the Philips standard and configurable //! pin mappings for I2S clock (BCLK), word select (WS), and data input/output @@ -18,33 +19,33 @@ //! supports various configurations, such as different data formats, standards //! (e.g., Philips) and pin configurations. It relies on other peripheral //! modules, such as -//! - `GPIO` -//! - `DMA` -//! - `system` (to configure and enable the I2S peripheral) +//! - `GPIO` +//! - `DMA` +//! - `system` (to configure and enable the I2S peripheral) +//! +//! ## Example //! -//! ## Examples //! ### Initialization +//! //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::i2s::I2s; //! # use esp_hal::i2s::Standard; //! # use esp_hal::i2s::DataFormat; +//! # use esp_hal::i2s::I2sReadDma; //! # use esp_hal::gpio::Io; //! # use esp_hal::dma_buffers; //! # use esp_hal::dma::{Dma, DmaPriority}; -//! # use crate::esp_hal::prelude::_fugit_RateExtU32; -//! # use crate::esp_hal::peripherals::Peripherals; -//! # use crate::esp_hal::i2s::I2sReadDma; -//! # use core::ptr::addr_of_mut; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); -//! let dma = Dma::new(peripherals.DMA); +//! let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! let dma = Dma::new(system.peripherals.DMA); #![cfg_attr(any(esp32, esp32s2), doc = "let dma_channel = dma.i2s0channel;")] #![cfg_attr(not(any(esp32, esp32s2)), doc = "let dma_channel = dma.channel0;")] //! let (_, tx_descriptors, mut rx_buffer, rx_descriptors) = //! dma_buffers!(0, 4 * 4092); //! //! let i2s = I2s::new( -//! peripherals.I2S0, +//! system.peripherals.I2S0, //! Standard::Philips, //! DataFormat::Data16Channel16, //! 44100.Hz(), @@ -54,7 +55,7 @@ //! ), //! tx_descriptors, //! rx_descriptors, -//! &clocks, +//! &system.clocks, //! ); #![cfg_attr(not(esp32), doc = "let i2s = i2s.with_mclk(io.pins.gpio0);")] //! let mut i2s_rx = i2s.i2s_rx diff --git a/esp-hal/src/interrupt/mod.rs b/esp-hal/src/interrupt/mod.rs index d082f93d81f..8831611fedf 100644 --- a/esp-hal/src/interrupt/mod.rs +++ b/esp-hal/src/interrupt/mod.rs @@ -30,19 +30,7 @@ //! //! ```rust, no_run #![doc = crate::before_snippet!()] -//! # use core::cell::RefCell; -//! -//! # use critical_section::Mutex; -//! # use esp_hal::{ -//! # prelude::*, -//! # system::{SoftwareInterrupt, SystemControl}, -//! # }; -//! # use esp_hal::interrupt::Priority; -//! # use esp_hal::interrupt::InterruptHandler; -//! -//! static SWINT0: Mutex>>> = -//! Mutex::new(RefCell::new(None)); -//! +//! let system = esp_hal::init(CpuClock::boot_default()); //! let mut sw_int = system.software_interrupt_control; //! critical_section::with(|cs| { //! sw_int @@ -58,15 +46,19 @@ //! }); //! //! loop {} -//! } +//! # } //! -//! # use procmacros::handler; -//! # use esp_hal::interrupt; -//! # use critical_section::Mutex; //! # use core::cell::RefCell; +//! # +//! # use critical_section::Mutex; //! # use esp_hal::system::SoftwareInterrupt; -//! # static SWINT0: Mutex>>> = Mutex::new(RefCell::new(None)); -//! #[handler(priority = esp_hal::interrupt::Priority::Priority1)] +//! # use esp_hal::interrupt::Priority; +//! # use esp_hal::interrupt::InterruptHandler; +//! # +//! static SWINT0: Mutex>>> = +//! Mutex::new(RefCell::new(None)); +//! +//! #[handler(priority = Priority::Priority1)] //! fn swint0_handler() { //! // esp_println::println!("SW interrupt0"); //! critical_section::with(|cs| { diff --git a/esp-hal/src/lcd_cam/cam.rs b/esp-hal/src/lcd_cam/cam.rs index a37a6f40fe3..b45523c16b7 100644 --- a/esp-hal/src/lcd_cam/cam.rs +++ b/esp-hal/src/lcd_cam/cam.rs @@ -21,9 +21,10 @@ //! # use fugit::RateExtU32; //! # use esp_hal::dma_buffers; //! # use esp_hal::dma::{Dma, DmaPriority}; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); //! -//! # let dma = Dma::new(peripherals.DMA); +//! # let dma = Dma::new(system.peripherals.DMA); //! # let channel = dma.channel0; //! //! # let (tx_buffer, tx_descriptors, _, rx_descriptors) = dma_buffers!(32678, 0); @@ -48,14 +49,14 @@ //! io.pins.gpio16, //! ); //! -//! let lcd_cam = LcdCam::new(peripherals.LCD_CAM); +//! let lcd_cam = LcdCam::new(system.peripherals.LCD_CAM); //! let mut camera = Camera::new( //! lcd_cam.cam, //! channel.rx, //! rx_descriptors, //! data_pins, //! 20u32.MHz(), -//! &clocks +//! &system.clocks //! ) //! // Remove this for slave mode. //! .with_master_clock(mclk_pin) diff --git a/esp-hal/src/lcd_cam/lcd/i8080.rs b/esp-hal/src/lcd_cam/lcd/i8080.rs index 0a67505bda9..a5b6272ddb4 100644 --- a/esp-hal/src/lcd_cam/lcd/i8080.rs +++ b/esp-hal/src/lcd_cam/lcd/i8080.rs @@ -1,14 +1,17 @@ //! # LCD - I8080/MOTO6800 Mode. //! //! ## Overview +//! //! The LCD_CAM peripheral I8080 driver provides support for the I8080 -//! format/timing. The driver mandates DMA for DMA (Direct Memory Access) for +//! format/timing. The driver mandates DMA (Direct Memory Access) for //! efficient data transfer. //! -//! ## Examples +//! ## Example +//! //! ### MIPI-DSI Display -//! Following code show how to send a command to a MIPI-DSI display over I8080 -//! protocol. +//! +//! The following example shows how to send a command to a MIPI-DSI display over +//! the I8080 protocol. //! //! ```rust, no_run #![doc = crate::before_snippet!()] @@ -16,11 +19,11 @@ //! # use esp_hal::lcd_cam::{LcdCam, lcd::i8080::{Config, I8080, TxEightBits}}; //! # use esp_hal::dma_buffers; //! # use esp_hal::dma::{Dma, DmaPriority}; -//! # use fugit::RateExtU32; -//! -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # +//! let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); //! -//! # let dma = Dma::new(peripherals.DMA); +//! # let dma = Dma::new(system.peripherals.DMA); //! # let channel = dma.channel0; //! //! # let (tx_buffer, tx_descriptors, _, rx_descriptors) = dma_buffers!(32678, 0); @@ -40,7 +43,7 @@ //! io.pins.gpio16, //! io.pins.gpio15, //! ); -//! let lcd_cam = LcdCam::new(peripherals.LCD_CAM); +//! let lcd_cam = LcdCam::new(system.peripherals.LCD_CAM); //! //! let mut i8080 = I8080::new( //! lcd_cam.lcd, @@ -49,7 +52,7 @@ //! tx_pins, //! 20.MHz(), //! Config::default(), -//! &clocks, +//! &system.clocks, //! ) //! .with_ctrl_pins(io.pins.gpio0, io.pins.gpio47); //! diff --git a/esp-hal/src/ledc/mod.rs b/esp-hal/src/ledc/mod.rs index f37af1fbef2..31fe16fe549 100644 --- a/esp-hal/src/ledc/mod.rs +++ b/esp-hal/src/ledc/mod.rs @@ -18,8 +18,10 @@ //! ## Examples //! //! ### Low Speed Channel -//! The following will configure the Low Speed Channel0 to 24kHz output with -//! 10% duty using the ABPClock +//! +//! The following example will configure the Low Speed Channel0 to 24kHz output +//! with 10% duty using the ABPClock. +//! //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::ledc::Ledc; @@ -28,14 +30,12 @@ //! # use esp_hal::ledc::LowSpeed; //! # use esp_hal::ledc::channel; //! # use esp_hal::gpio::Io; -//! # use crate::esp_hal::prelude::_esp_hal_ledc_timer_TimerIFace; -//! # use crate::esp_hal::prelude::_fugit_RateExtU32; -//! # use crate::esp_hal::prelude::_esp_hal_ledc_channel_ChannelIFace; //! -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); //! # let led = io.pins.gpio0; //! -//! let mut ledc = Ledc::new(peripherals.LEDC, &clocks); +//! let mut ledc = Ledc::new(system.peripherals.LEDC, &system.clocks); //! ledc.set_global_slow_clock(LSGlobalClkSource::APBClk); //! //! let mut lstimer0 = ledc.get_timer::(timer::Number::Timer0); diff --git a/esp-hal/src/lib.rs b/esp-hal/src/lib.rs index 1af867cfc8a..ebf9e3bcdcc 100644 --- a/esp-hal/src/lib.rs +++ b/esp-hal/src/lib.rs @@ -17,7 +17,7 @@ #![cfg_attr(esp32c3, doc = "**ESP32-C3**")] #![cfg_attr(esp32c6, doc = "**ESP32-C6**")] #![cfg_attr(esp32h2, doc = "**ESP32-H2**")] -//! please ensure you are reading the correct [documentation] for your target +//! . Please ensure you are reading the correct [documentation] for your target //! device. //! //! ## Choosing a Device @@ -63,12 +63,9 @@ //! // A panic - handler e.g. `use esp_backtrace as _;` //! //! use esp_hal::{ -//! clock::ClockControl, //! delay::Delay, //! gpio::{Io, Level, Output}, -//! peripherals::Peripherals, //! prelude::*, -//! system::SystemControl, //! }; //! # #[panic_handler] //! # fn panic(_ : &core::panic::PanicInfo) -> ! { @@ -77,15 +74,13 @@ //! //! #[entry] //! fn main() -> ! { -//! let peripherals = Peripherals::take(); -//! let system = SystemControl::new(peripherals.SYSTEM); -//! let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); +//! let system = esp_hal::init(CpuClock::boot_default()); //! //! // Set GPIO0 as an output, and set its state high initially. -//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); //! let mut led = Output::new(io.pins.gpio0, Level::High); //! -//! let delay = Delay::new(&clocks); +//! let delay = Delay::new(&system.clocks); //! //! loop { //! led.toggle(); @@ -626,17 +621,40 @@ macro_rules! before_snippet { () => { r#" # #![no_std] -# use esp_hal::peripherals::Peripherals; -# use esp_hal::clock::ClockControl; -# use esp_hal::system::SystemControl; +# use esp_hal::prelude::*; # #[panic_handler] # fn panic(_ : &core::panic::PanicInfo) -> ! { # loop {} # } # fn main() { -# let peripherals = Peripherals::take(); -# let system = SystemControl::new(peripherals.SYSTEM); -# let mut clocks = ClockControl::boot_defaults(system.clock_control).freeze(); "# }; } + +use crate::{ + clock::{ClockControl, Clocks, CpuClock}, + peripherals::Peripherals, +}; + +/// System components. +pub struct System { + /// The available peripheral instances. + pub peripherals: Peripherals, + + /// The configured clocks. + pub clocks: Clocks<'static>, + + /// The available software interrupts. + pub software_interrupt_control: crate::system::SoftwareInterruptControl, +} + +/// Initialize the system. +pub fn init(clock_config: CpuClock) -> System { + let peripherals = Peripherals::take(); + + System { + peripherals, + clocks: ClockControl::new(clock_config).freeze(), + software_interrupt_control: crate::system::SoftwareInterruptControl::new(), + } +} diff --git a/esp-hal/src/mcpwm/mod.rs b/esp-hal/src/mcpwm/mod.rs index 94d84909a44..9803dce07be 100644 --- a/esp-hal/src/mcpwm/mod.rs +++ b/esp-hal/src/mcpwm/mod.rs @@ -42,29 +42,32 @@ #![cfg_attr(esp32h2, doc = "Clock source is XTAL")] #![doc = ""] //! ## Examples +//! //! ### Output a 20 kHz signal -//! Uses timer0 and operator0 of the MCPWM0 peripheral to output a 50% duty -//! signal at 20 kHz. The signal will be output to the pin assigned to `pin`. +//! +//! This example uses timer0 and operator0 of the MCPWM0 peripheral to output a +//! 50% duty signal at 20 kHz. The signal will be output to the pin assigned to +//! `pin`. +//! //! ```rust, no_run #![doc = crate::before_snippet!()] -//! # use esp_hal::{mcpwm, prelude::*}; -//! # use esp_hal::mcpwm::operator::{DeadTimeCfg, PWMStream}; -//! # use mcpwm::{operator::PwmPinConfig, timer::PwmWorkingMode, McPwm, PeripheralClockConfig}; +//! # use esp_hal::mcpwm::{operator::{DeadTimeCfg, PWMStream, PwmPinConfig}, timer::PwmWorkingMode, McPwm, PeripheralClockConfig}; //! # use esp_hal::gpio::Io; //! -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); //! # let pin = io.pins.gpio0; //! //! // initialize peripheral #![cfg_attr( esp32h2, - doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&clocks, 40.MHz()).unwrap();" + doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&system.clocks, 40.MHz()).unwrap();" )] #![cfg_attr( not(esp32h2), - doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&clocks, 32.MHz()).unwrap();" + doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&system.clocks, 32.MHz()).unwrap();" )] -//! let mut mcpwm = McPwm::new(peripherals.MCPWM0, clock_cfg); +//! let mut mcpwm = McPwm::new(system.peripherals.MCPWM0, clock_cfg); //! //! // connect operator0 to timer0 //! mcpwm.operator0.set_timer(&mcpwm.timer0); diff --git a/esp-hal/src/mcpwm/operator.rs b/esp-hal/src/mcpwm/operator.rs index de6c5fe3517..3e7ee48fb37 100644 --- a/esp-hal/src/mcpwm/operator.rs +++ b/esp-hal/src/mcpwm/operator.rs @@ -479,13 +479,15 @@ impl<'d, Pin: OutputPin, PWM: PwmPeripheral, const OP: u8, const IS_A: bool> /// configured deadtime. /// /// # H-Bridge example +/// /// ```rust, no_run #[doc = crate::before_snippet!()] /// # use esp_hal::{mcpwm, prelude::*}; /// # use esp_hal::mcpwm::{McPwm, PeripheralClockConfig}; /// # use esp_hal::mcpwm::operator::{DeadTimeCfg, PwmPinConfig, PWMStream}; /// # use esp_hal::gpio::Io; -/// # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +/// let system = esp_hal::init(CpuClock::boot_default()); +/// # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); /// // active high complementary using PWMA input /// let bridge_active = DeadTimeCfg::new_ahc(); /// // use PWMB as input for both outputs @@ -493,13 +495,13 @@ impl<'d, Pin: OutputPin, PWM: PwmPeripheral, const OP: u8, const IS_A: bool> /// true); #[cfg_attr( esp32h2, - doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&clocks, 40.MHz()).unwrap();" + doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&system.clocks, 40.MHz()).unwrap();" )] #[cfg_attr( not(esp32h2), - doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&clocks, 32.MHz()).unwrap();" + doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&system.clocks, 32.MHz()).unwrap();" )] -/// let mut mcpwm = McPwm::new(peripherals.MCPWM0, clock_cfg); +/// let mut mcpwm = McPwm::new(system.peripherals.MCPWM0, clock_cfg); /// /// let mut pins = mcpwm.operator0.with_linked_pins( /// io.pins.gpio0, diff --git a/esp-hal/src/prelude.rs b/esp-hal/src/prelude.rs index 32c9a1cd8a5..41a19827407 100644 --- a/esp-hal/src/prelude.rs +++ b/esp-hal/src/prelude.rs @@ -38,4 +38,4 @@ pub use crate::timer::timg::{ pub use crate::timer::Timer as _esp_hal_timer_Timer; #[cfg(any(uart0, uart1, uart2))] pub use crate::uart::Instance as _esp_hal_uart_Instance; -pub use crate::{entry, macros::*, InterruptConfigurable}; +pub use crate::{clock::CpuClock, entry, macros::*, InterruptConfigurable, System}; diff --git a/esp-hal/src/rmt.rs b/esp-hal/src/rmt.rs index d3ee8abd2a1..f4a981d84ee 100644 --- a/esp-hal/src/rmt.rs +++ b/esp-hal/src/rmt.rs @@ -18,24 +18,25 @@ //! the input signal //! //! ### Channels +//! //! There are #![cfg_attr( esp32, - doc = "8 channels, each of them can be either receiver or transmitter" + doc = "8 channels, each of them can be either receiver or transmitter." )] #![cfg_attr( esp32s2, - doc = "4 channels, each of them can be either receiver or transmitter" + doc = "4 channels, each of them can be either receiver or transmitter." )] #![cfg_attr( esp32s3, - doc = "8 channels, `Channel<0>`-`Channel<3>` hardcoded for transmitting signals and `Channel<4>`-`Channel<7>` hardcoded for receiving signals" + doc = "8 channels, `Channel<0>`-`Channel<3>` hardcoded for transmitting signals and `Channel<4>`-`Channel<7>` hardcoded for receiving signals." )] #![cfg_attr( any(esp32c3, esp32c6, esp32h2), doc = "4 channels, `Channel<0>` and `Channel<1>` hardcoded for transmitting signals and `Channel<2>` and `Channel<3>` hardcoded for receiving signals." )] -#![doc = " "] +#![doc = ""] //! For more information, please refer to the #![doc = concat!("[ESP-IDF documentation](https://docs.espressif.com/projects/esp-idf/en/latest/", crate::soc::chip!(), "/api-reference/peripherals/rmt.html)")] //! ## Configuration @@ -44,8 +45,10 @@ //! channels are indicated by n which is used as a placeholder for the channel //! number, and by m for RX channels. //! -//! ## Examples +//! ## Example +//! //! ### Initialization +//! //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::peripherals::Peripherals; @@ -55,10 +58,11 @@ //! # use esp_hal::clock::ClockControl; //! # use crate::esp_hal::rmt::TxChannelCreator; //! # use crate::esp_hal::prelude::_fugit_RateExtU32; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); #![cfg_attr(esp32h2, doc = "let freq = 32.MHz();")] #![cfg_attr(not(esp32h2), doc = "let freq = 80.MHz();")] -//! let rmt = Rmt::new(peripherals.RMT, freq, &clocks).unwrap(); +//! let rmt = Rmt::new(system.peripherals.RMT, freq, &system.clocks).unwrap(); //! let mut channel = rmt //! .channel0 //! .configure( @@ -76,8 +80,8 @@ //! .unwrap(); //! # } //! ``` -//! (on ESP32 and ESP32-S2 you cannot specify a base frequency other than 80 -//! MHz) +//! +//! > Note: on ESP32 and ESP32-S2 you cannot specify a base frequency other than 80 MHz use core::marker::PhantomData; diff --git a/esp-hal/src/rom/md5.rs b/esp-hal/src/rom/md5.rs index cfae6ebba9c..4759219b49b 100644 --- a/esp-hal/src/rom/md5.rs +++ b/esp-hal/src/rom/md5.rs @@ -35,8 +35,9 @@ //! # use esp_hal::gpio::Io; //! # use core::writeln; //! # use core::fmt::Write; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); -//! # let mut uart0 = Uart::new(peripherals.UART0, &clocks, io.pins.gpio1, io.pins.gpio2).unwrap(); +//! # let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let mut uart0 = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio1, io.pins.gpio2).unwrap(); //! # let data = "Dummy"; //! let d: md5::Digest = md5::compute(&data); //! writeln!(uart0, "{}", d); @@ -51,10 +52,12 @@ //! # use esp_hal::gpio::Io; //! # use core::writeln; //! # use core::fmt::Write; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); -//! # let mut uart0 = Uart::new(peripherals.UART0, &clocks, io.pins.gpio1, io.pins.gpio2).unwrap(); +//! # let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let mut uart0 = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio1, io.pins.gpio2).unwrap(); //! # let data0 = "Dummy"; //! # let data1 = "Dummy"; +//! # //! let mut ctx = md5::Context::new(); //! ctx.consume(&data0); //! ctx.consume(&data1); diff --git a/esp-hal/src/rtc_cntl/mod.rs b/esp-hal/src/rtc_cntl/mod.rs index cfbf13f0756..492a6de0c9f 100644 --- a/esp-hal/src/rtc_cntl/mod.rs +++ b/esp-hal/src/rtc_cntl/mod.rs @@ -14,11 +14,10 @@ //! * Clock Configuration //! * Calibration //! * Low-Power Management -//! * Real-Time Clock //! * Handling Watchdog Timers //! -//! ## Examples -//! ### Print Time in Milliseconds From the RTC Timer +//! ## Example +//! //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use core::cell::RefCell; @@ -30,31 +29,28 @@ //! # use crate::esp_hal::prelude::_fugit_ExtU64; //! # use crate::esp_hal::InterruptConfigurable; //! static RWDT: Mutex>> = Mutex::new(RefCell::new(None)); -//! let mut delay = Delay::new(&clocks); //! -//! let mut rtc = Rtc::new(peripherals.LPWR); +//! let system = esp_hal::init(CpuClock::boot_default()); +//! let mut delay = Delay::new(&system.clocks); +//! +//! let mut rtc = Rtc::new(system.peripherals.LPWR); +//! //! rtc.set_interrupt_handler(interrupt_handler); //! rtc.rwdt.set_timeout(2000.millis()); //! rtc.rwdt.listen(); //! //! critical_section::with(|cs| RWDT.borrow_ref_mut(cs).replace(rtc.rwdt)); -//! -//! -//! loop {} //! # } //! //! // Where the `LP_WDT` interrupt handler is defined as: -//! // Handle the corresponding interrupt //! # use core::cell::RefCell; //! //! # use critical_section::Mutex; -//! # use esp_hal::prelude::handler; -//! # use esp_hal::interrupt::InterruptHandler; -//! # use esp_hal::interrupt; -//! # use esp_hal::interrupt::Priority; -//! # use crate::esp_hal::prelude::_fugit_ExtU64; //! # use esp_hal::rtc_cntl::Rwdt; +//! //! static RWDT: Mutex>> = Mutex::new(RefCell::new(None)); +//! +//! // Handle the corresponding interrupt //! #[handler] //! fn interrupt_handler() { //! critical_section::with(|cs| { diff --git a/esp-hal/src/soc/esp32/efuse/mod.rs b/esp-hal/src/soc/esp32/efuse/mod.rs index 63eff59fb7c..4e275bd4298 100644 --- a/esp-hal/src/soc/esp32/efuse/mod.rs +++ b/esp-hal/src/soc/esp32/efuse/mod.rs @@ -28,8 +28,9 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); -//! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); +//! # let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let mut serial_tx = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32c2/efuse/mod.rs b/esp-hal/src/soc/esp32c2/efuse/mod.rs index 93db7e33dca..1e1981cba3d 100644 --- a/esp-hal/src/soc/esp32c2/efuse/mod.rs +++ b/esp-hal/src/soc/esp32c2/efuse/mod.rs @@ -25,8 +25,9 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); -//! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); +//! # let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let mut serial_tx = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32c3/efuse/mod.rs b/esp-hal/src/soc/esp32c3/efuse/mod.rs index 08d81adf092..a897fad9444 100644 --- a/esp-hal/src/soc/esp32c3/efuse/mod.rs +++ b/esp-hal/src/soc/esp32c3/efuse/mod.rs @@ -26,8 +26,9 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); -//! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); +//! # let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let mut serial_tx = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32c6/efuse/mod.rs b/esp-hal/src/soc/esp32c6/efuse/mod.rs index a49f21870c1..73f8fecc5fd 100644 --- a/esp-hal/src/soc/esp32c6/efuse/mod.rs +++ b/esp-hal/src/soc/esp32c6/efuse/mod.rs @@ -26,8 +26,9 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); -//! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); +//! # let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let mut serial_tx = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32h2/efuse/mod.rs b/esp-hal/src/soc/esp32h2/efuse/mod.rs index fbf928a8dec..745679d4e72 100644 --- a/esp-hal/src/soc/esp32h2/efuse/mod.rs +++ b/esp-hal/src/soc/esp32h2/efuse/mod.rs @@ -26,8 +26,9 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); -//! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); +//! # let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let mut serial_tx = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32s2/efuse/mod.rs b/esp-hal/src/soc/esp32s2/efuse/mod.rs index bebbf7a1976..569ce1871ea 100644 --- a/esp-hal/src/soc/esp32s2/efuse/mod.rs +++ b/esp-hal/src/soc/esp32s2/efuse/mod.rs @@ -28,8 +28,9 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); -//! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); +//! # let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let mut serial_tx = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32s2/ulp_core.rs b/esp-hal/src/soc/esp32s2/ulp_core.rs index 579317b2a8f..1e027659c34 100644 --- a/esp-hal/src/soc/esp32s2/ulp_core.rs +++ b/esp-hal/src/soc/esp32s2/ulp_core.rs @@ -17,17 +17,22 @@ #![doc = crate::before_snippet!()] //! const CODE: &[u8] = &[ //! 0x17, 0x05, 0x00, 0x00, 0x13, 0x05, 0x05, 0x01, 0x81, 0x45, 0x85, 0x05, -//! 0x0c, 0xc1, 0xf5, 0xbf, 0x00, 0x00, 0x00, 0x00, -//! ]; +//! 0x0c, 0xc1, 0xf5, 0xbf, 0x00, 0x00, 0x00, 0x00, +//! ]; +//! let system = esp_hal::init(CpuClock::boot_default()); //! let mut ulp_core = -//! esp_hal::ulp_core::UlpCore::new(peripherals.ULP_RISCV_CORE); +//! esp_hal::ulp_core::UlpCore::new(system.peripherals.ULP_RISCV_CORE); //! // ulp_core.stop(); currently not implemented //! //! // copy code to RTC ram //! let lp_ram = 0x5000_0000 as *mut u8; //! unsafe { -//! core::ptr::copy_nonoverlapping(CODE as *const _ as *const u8, lp_ram, -//! CODE.len()); } +//! core::ptr::copy_nonoverlapping( +//! CODE as *const _ as *const u8, +//! lp_ram, +//! CODE.len(), +//! ); +//! } //! //! // start ULP core //! ulp_core.run(esp_hal::ulp_core::UlpCoreWakeupSource::HpCpu); diff --git a/esp-hal/src/soc/esp32s3/cpu_control.rs b/esp-hal/src/soc/esp32s3/cpu_control.rs index 403ddd98887..a9e24e3ada9 100644 --- a/esp-hal/src/soc/esp32s3/cpu_control.rs +++ b/esp-hal/src/soc/esp32s3/cpu_control.rs @@ -13,20 +13,22 @@ //! # use esp_hal::cpu_control::{CpuControl, Stack}; //! # use core::{cell::RefCell, ptr::addr_of_mut}; //! # use critical_section::Mutex; -//! # use esp_hal::prelude::*; //! static mut APP_CORE_STACK: Stack<8192> = Stack::new(); +//! let system = esp_hal::init(CpuClock::boot_default()); //! -//! # let delay = Delay::new(&clocks); +//! # let delay = Delay::new(&system.clocks); //! //! let counter = Mutex::new(RefCell::new(0)); //! -//! let mut cpu_control = CpuControl::new(peripherals.CPU_CTRL); +//! let mut cpu_control = CpuControl::new(system.peripherals.CPU_CTRL); //! let cpu1_fnctn = || { //! cpu1_task(&delay, &counter); //! }; //! let _guard = cpu_control -//! .start_app_core(unsafe { &mut *addr_of_mut!(APP_CORE_STACK) }, -//! cpu1_fnctn) .unwrap(); +//! .start_app_core( +//! unsafe { &mut *addr_of_mut!(APP_CORE_STACK) }, +//! cpu1_fnctn, +//! ).unwrap(); //! //! loop { //! delay.delay(1.secs()); @@ -37,7 +39,7 @@ //! // Where `cpu1_task()` may be defined as: //! # use esp_hal::delay::Delay; //! # use core::cell::RefCell; -//! # use esp_hal::prelude::*; +//! //! fn cpu1_task( //! delay: &Delay, //! counter: &critical_section::Mutex>, diff --git a/esp-hal/src/soc/esp32s3/efuse/mod.rs b/esp-hal/src/soc/esp32s3/efuse/mod.rs index 79445ae675d..a73fe786d4e 100644 --- a/esp-hal/src/soc/esp32s3/efuse/mod.rs +++ b/esp-hal/src/soc/esp32s3/efuse/mod.rs @@ -26,8 +26,9 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); -//! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); +//! # let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let mut serial_tx = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32s3/ulp_core.rs b/esp-hal/src/soc/esp32s3/ulp_core.rs index 865387bcb15..dd92e516431 100644 --- a/esp-hal/src/soc/esp32s3/ulp_core.rs +++ b/esp-hal/src/soc/esp32s3/ulp_core.rs @@ -1,6 +1,7 @@ //! Control the ULP core //! //! ## Overview +//! //! The `ULP CORE` peripheral allows control over the `Ultra-Low Power //! (ULP) core` in `ESP` chips. The ULP core is a low-power processor //! designed for executing tasks in deep sleep mode, enabling efficient power @@ -11,22 +12,30 @@ //! operation. The `UlpCore` struct is initialized with a peripheral reference //! to the `ULP CORE` instance. //! -//! ## Examples +//! ## Example +//! //! ```rust, no_run #![doc = crate::before_snippet!()] +//! let system = esp_hal::init(CpuClock::boot_default()); +//! //! const CODE: &[u8] = &[ //! 0x17, 0x05, 0x00, 0x00, 0x13, 0x05, 0x05, 0x01, 0x81, 0x45, 0x85, 0x05, -//! 0x0c, 0xc1, 0xf5, 0xbf, 0x00, 0x00, 0x00, 0x00, -//! ]; +//! 0x0c, 0xc1, 0xf5, 0xbf, 0x00, 0x00, 0x00, 0x00, +//! ]; +//! //! let mut ulp_core = -//! esp_hal::ulp_core::UlpCore::new(peripherals.ULP_RISCV_CORE); +//! esp_hal::ulp_core::UlpCore::new(system.peripherals.ULP_RISCV_CORE); //! ulp_core.stop(); //! //! // copy code to RTC ram //! let lp_ram = 0x5000_0000 as *mut u8; //! unsafe { -//! core::ptr::copy_nonoverlapping(CODE as *const _ as *const u8, lp_ram, -//! CODE.len()); } +//! core::ptr::copy_nonoverlapping( +//! CODE as *const _ as *const u8, +//! lp_ram, +//! CODE.len(), +//! ); +//! } //! //! // start ULP core //! ulp_core.run(esp_hal::ulp_core::UlpCoreWakeupSource::HpCpu); diff --git a/esp-hal/src/spi/master.rs b/esp-hal/src/spi/master.rs index b65b28d805c..cc529c11ceb 100644 --- a/esp-hal/src/spi/master.rs +++ b/esp-hal/src/spi/master.rs @@ -42,17 +42,18 @@ //! # use esp_hal::spi::SpiMode; //! # use esp_hal::spi::master::Spi; //! # use esp_hal::gpio::Io; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); //! let sclk = io.pins.gpio0; //! let miso = io.pins.gpio2; //! let mosi = io.pins.gpio1; //! let cs = io.pins.gpio5; //! //! let mut spi = Spi::new( -//! peripherals.SPI2, +//! system.peripherals.SPI2, //! 100.kHz(), //! SpiMode::Mode0, -//! &mut clocks, +//! &system.clocks, //! ) //! .with_pins(Some(sclk), Some(mosi), Some(miso), Some(cs)); //! # } diff --git a/esp-hal/src/spi/slave.rs b/esp-hal/src/spi/slave.rs index 52491f57fdb..2eabc47ec77 100644 --- a/esp-hal/src/spi/slave.rs +++ b/esp-hal/src/spi/slave.rs @@ -21,10 +21,11 @@ //! # use esp_hal::spi::slave::{prelude::*, Spi}; //! # use esp_hal::dma::Dma; //! # use esp_hal::gpio::Io; -//! let dma = Dma::new(peripherals.DMA); +//! let system = esp_hal::init(CpuClock::boot_default()); +//! let dma = Dma::new(system.peripherals.DMA); #![cfg_attr(esp32s2, doc = "let dma_channel = dma.spi2channel;")] #![cfg_attr(not(esp32s2), doc = "let dma_channel = dma.channel0;")] -//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); //! let sclk = io.pins.gpio0; //! let miso = io.pins.gpio1; //! let mosi = io.pins.gpio2; @@ -32,7 +33,7 @@ //! //! let (tx_buffer, tx_descriptors, rx_buffer, rx_descriptors) = //! dma_buffers!(32000); let mut spi = Spi::new( -//! peripherals.SPI2, +//! system.peripherals.SPI2, //! sclk, //! mosi, //! miso, @@ -48,8 +49,8 @@ //! let mut receive = rx_buffer; //! //! let transfer = spi -//! .dma_transfer(&mut send, &mut receive) -//! .unwrap(); +//! .dma_transfer(&mut send, &mut receive) +//! .unwrap(); //! //! transfer.wait().unwrap(); //! # } diff --git a/esp-hal/src/system.rs b/esp-hal/src/system.rs index 1c31a0e611b..d807269c5bd 100755 --- a/esp-hal/src/system.rs +++ b/esp-hal/src/system.rs @@ -1,46 +1,60 @@ //! # System Control //! //! ## Overview +//! //! This `system` driver provides an interface to control and configure various //! system-related features and peripherals on ESP chips. It includes //! functionality to control peripheral clocks, manage software interrupts, //! configure chip clocks, and control radio peripherals. //! -//! ### Software Interrupts +//! ## Software Interrupts +//! //! The `SoftwareInterruptControl` struct gives access to the available software //! interrupts. //! //! The `SoftwareInterrupt` struct allows raising or resetting software //! interrupts using the `raise()` and `reset()` methods. //! -//! ### Peripheral Clock Control -//! The `PeripheralClockControl` struct controls the enablement of peripheral -//! clocks. +//! ### Examples //! -//! It provides an `enable()` method to enable and reset specific peripherals. -//! The available peripherals are represented by the `Peripheral` enum -//! -//! ## Examples //! ```rust, no_run #![doc = crate::before_snippet!()] -//! let peripherals = Peripherals::take(); -//! let system = SystemControl::new(peripherals.SYSTEM); -//! let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); +//! let system = esp_hal::init(CpuClock::boot_default()); +//! +//! let mut int0 = system.software_interrupt_control.software_interrupt0; +//! +//! critical_section::with(|cs| { +//! int0.set_interrupt_handler(interrupt_handler); +//! SWINT0.borrow_ref_mut(cs).replace(int0); +//! }); //! # } +//! +//! use core::cell::RefCell; +//! use critical_section::Mutex; +//! use esp_hal::system::SoftwareInterrupt; +//! +//! static SWINT0: Mutex>>> = +//! Mutex::new(RefCell::new(None)); +//! +//! #[handler] +//! fn interrupt_handler() { +//! // esp_println::println!("SW interrupt0"); +//! critical_section::with(|cs| { +//! SWINT0.borrow_ref(cs).as_ref().unwrap().reset(); +//! }); +//! } //! ``` -use crate::{ - interrupt::InterruptHandler, - peripheral::PeripheralRef, - peripherals::SYSTEM, - InterruptConfigurable, -}; +use crate::{interrupt::InterruptHandler, peripherals::SYSTEM, InterruptConfigurable}; /// Peripherals which can be enabled via `PeripheralClockControl`. /// /// This enum represents various hardware peripherals that can be enabled /// by the system's clock control. Depending on the target device, different /// peripherals will be available for enabling. +// FIXME: This enum needs to be public because it's exposed via a bunch of traits, but it's not +// useful to users. +#[doc(hidden)] pub enum Peripheral { /// SPI2 peripheral. #[cfg(spi2)] @@ -146,30 +160,6 @@ pub enum Peripheral { Systimer, } -/// The `DPORT`/`PCR`/`SYSTEM` peripheral split into its different logical -/// components. -pub struct SystemControl<'d> { - /// Inner reference to the SYSTEM peripheral. - _inner: PeripheralRef<'d, SYSTEM>, - /// Controls the system's clock settings and configurations. - pub clock_control: SystemClockControl, - /// Controls the system's software interrupt settings. - pub software_interrupt_control: SoftwareInterruptControl, -} - -impl<'d> SystemControl<'d> { - /// Construct a new instance of [`SystemControl`]. - pub fn new(system: impl crate::peripheral::Peripheral

+ 'd) -> Self { - crate::into_ref!(system); - - Self { - _inner: system, - clock_control: SystemClockControl::new(), - software_interrupt_control: SoftwareInterruptControl::new(), - } - } -} - /// A software interrupt can be triggered by software. #[non_exhaustive] pub struct SoftwareInterrupt; @@ -312,7 +302,7 @@ pub struct SoftwareInterruptControl { } impl SoftwareInterruptControl { - fn new() -> Self { + pub(crate) fn new() -> Self { SoftwareInterruptControl { software_interrupt0: SoftwareInterrupt {}, software_interrupt1: SoftwareInterrupt {}, diff --git a/esp-hal/src/timer/mod.rs b/esp-hal/src/timer/mod.rs index 313772472ad..fb7ae3fb146 100644 --- a/esp-hal/src/timer/mod.rs +++ b/esp-hal/src/timer/mod.rs @@ -17,8 +17,9 @@ //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::timer::{OneShotTimer, PeriodicTimer, timg::TimerGroup}; -//! # use esp_hal::prelude::*; -//! let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); +//! # +//! let system = esp_hal::init(CpuClock::boot_default()); +//! let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); //! let one_shot = OneShotTimer::new(timg0.timer0); //! //! one_shot.delay_millis(500); @@ -29,8 +30,9 @@ //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::timer::{PeriodicTimer, timg::TimerGroup}; -//! # use esp_hal::prelude::*; -//! let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); +//! # +//! let system = esp_hal::init(CpuClock::boot_default()); +//! let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); //! let mut periodic = PeriodicTimer::new(timg0.timer0); //! //! periodic.start(1.secs()); diff --git a/esp-hal/src/timer/systimer.rs b/esp-hal/src/timer/systimer.rs index 21013044343..43ee99807bd 100644 --- a/esp-hal/src/timer/systimer.rs +++ b/esp-hal/src/timer/systimer.rs @@ -15,58 +15,59 @@ //! [Alarm]s can be configured in two modes: [Target] (one-shot) and [Periodic]. //! //! ## Examples -//! ### General-purpose Timer -//! ```rust, no_run -#![doc = crate::before_snippet!()] -//! # use esp_hal::timer::systimer::SystemTimer; -//! # use esp_hal::timer::timg::TimerGroup; -//! # use crate::esp_hal::prelude::_esp_hal_timer_Timer; -//! # use esp_hal::prelude::*; -//! let systimer = SystemTimer::new(peripherals.SYSTIMER); //! -//! // Get the current timestamp, in microseconds: -//! let now = SystemTimer::now(); +//! ### Splitting up the System Timer into three alarms //! -//! let timg0 = TimerGroup::new( -//! peripherals.TIMG0, -//! &clocks, -//! ); +//! Use the [split] method to create three alarms from the System Timer, +//! contained in a [SysTimerAlarms] struct. //! -//! let mut timer0 = timg0.timer0; -//! timer0.set_interrupt_handler(tg0_t0_level); +//! ```rust, no_run +#![doc = crate::before_snippet!()] +//! use esp_hal::timer::systimer::{ +//! SystemTimer, +//! Periodic, +//! }; //! -//! // Wait for timeout: -//! timer0.load_value(1.secs()); -//! timer0.start(); +//! let system = esp_hal::init(CpuClock::boot_default()); +//! let systimer = SystemTimer::new( +//! system.peripherals.SYSTIMER, +//! ).split::(); //! -//! while !timer0.is_interrupt_set() { -//! // Wait -//! } +//! // Reconfigure a periodic alarm to be a target alarm +//! let target_alarm = systimer.alarm0.into_target(); //! # } +//! ``` +//! +//! ### General-purpose Timer +//! ```rust, no_run +#![doc = crate::before_snippet!()] +//! use esp_hal::timer::systimer::{ +//! Alarm, +//! FrozenUnit, +//! SpecificUnit, +//! SystemTimer, +//! }; //! +//! let system = esp_hal::init(CpuClock::boot_default()); +//! let mut systimer = SystemTimer::new(system.peripherals.SYSTIMER); //! -//! # use core::cell::RefCell; -//! # use critical_section::Mutex; -//! # use procmacros::handler; -//! # use esp_hal::interrupt::InterruptHandler; -//! # use esp_hal::interrupt; -//! # use esp_hal::peripherals::TIMG0; -//! # use esp_hal::timer::timg::{Timer, Timer0}; -//! # use crate::esp_hal::prelude::_esp_hal_timer_Timer; -//! # static TIMER0: Mutex, esp_hal::Blocking>>>> = Mutex::new(RefCell::new(None)); -//! #[handler] -//! fn tg0_t0_level() { -//! critical_section::with(|cs| { -//! let mut timer0 = TIMER0.borrow_ref_mut(cs); -//! let timer0 = timer0.as_mut().unwrap(); +//! // Get the current timestamp, in microseconds: +//! let now = SystemTimer::now(); //! -//! timer0.clear_interrupt(); +//! let frozen_unit = FrozenUnit::new(&mut systimer.unit0); +//! let alarm0 = Alarm::new(systimer.comparator0, &frozen_unit); //! -//! // Counter value should be a very small number as the alarm triggered a -//! // counter reload to 0 and ETM stopped the counter quickly after -//! // esp_println::println!("counter in interrupt: {}", timer0.now()); -//! }); +//! alarm0.set_target( +//! SystemTimer::now() + SystemTimer::ticks_per_second() * 2 +//! ); +//! alarm0.enable_interrupt(true); +//! +//! while !alarm0.is_interrupt_set() { +//! // Wait for the interrupt to be set //! } +//! +//! alarm0.clear_interrupt(); +//! # } //! ``` use core::{ diff --git a/esp-hal/src/timer/timg.rs b/esp-hal/src/timer/timg.rs index 6b73e1e247d..1eb2243f6f5 100644 --- a/esp-hal/src/timer/timg.rs +++ b/esp-hal/src/timer/timg.rs @@ -27,9 +27,9 @@ //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::timer::timg::TimerGroup; -//! # use crate::esp_hal::prelude::_esp_hal_timer_Timer; -//! # use esp_hal::prelude::*; -//! let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); +//! +//! let system = esp_hal::init(CpuClock::boot_default()); +//! let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); //! let timer0 = timg0.timer0; //! //! // Get the current timestamp, in microseconds: @@ -42,6 +42,8 @@ //! while !timer0.is_interrupt_set() { //! // Wait //! } +//! +//! timer0.clear_interrupt(); //! # } //! ``` //! @@ -49,8 +51,9 @@ //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::timer::timg::TimerGroup; -//! # use esp_hal::prelude::*; -//! let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); +//! +//! let system = esp_hal::init(CpuClock::boot_default()); +//! let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); //! let mut wdt = timg0.wdt; //! //! wdt.set_timeout(5_000.millis()); diff --git a/esp-hal/src/twai/mod.rs b/esp-hal/src/twai/mod.rs index 562b1b9b851..b0ebab1dabf 100644 --- a/esp-hal/src/twai/mod.rs +++ b/esp-hal/src/twai/mod.rs @@ -35,7 +35,8 @@ //! # use esp_hal::gpio::Io; //! # use embedded_can::Frame; //! # use nb::block; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); //! // Use GPIO pins 2 and 3 to connect to the respective pins on the TWAI //! // transceiver. //! let can_tx_pin = io.pins.gpio2; @@ -47,10 +48,10 @@ //! // Begin configuring the TWAI peripheral. The peripheral is in a reset like //! // state that prevents transmission but allows configuration. //! let mut can_config = twai::TwaiConfiguration::new( -//! peripherals.TWAI0, +//! system.peripherals.TWAI0, //! can_tx_pin, //! can_rx_pin, -//! &clocks, +//! &system.clocks, //! TWAI_BAUDRATE, //! TwaiMode::Normal //! ); @@ -91,7 +92,8 @@ //! # use esp_hal::gpio::Io; //! # use embedded_can::Frame; //! # use nb::block; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); //! // Use GPIO pins 2 and 3 to connect to the respective pins on the TWAI //! // transceiver. //! let can_tx_pin = io.pins.gpio2; @@ -102,10 +104,10 @@ //! //! // Begin configuring the TWAI peripheral. //! let mut can_config = twai::TwaiConfiguration::new( -//! peripherals.TWAI0, +//! system.peripherals.TWAI0, //! can_tx_pin, //! can_rx_pin, -//! &clocks, +//! &system.clocks, //! TWAI_BAUDRATE, //! TwaiMode::SelfTest //! ); diff --git a/esp-hal/src/uart.rs b/esp-hal/src/uart.rs index c06aa380e15..0c2b56c6153 100644 --- a/esp-hal/src/uart.rs +++ b/esp-hal/src/uart.rs @@ -1,6 +1,7 @@ //! # Universal Asynchronous Receiver/Transmitter (UART) //! //! ## Overview +//! //! The UART is a hardware peripheral which handles communication using serial //! communication interfaces, such as RS232 and RS485. This peripheral provides //! a cheap and ubiquitous method for full- and half-duplex communication @@ -13,6 +14,7 @@ //! protocols. //! //! ## Configuration +//! //! Each UART controller is individually configurable, and the usual setting //! such as baud rate, data bits, parity, and stop bits can easily be //! configured. Additionally, the transmit (TX) and receive (RX) pins need to @@ -22,18 +24,25 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::uart::{config::Config, Uart}; //! use esp_hal::gpio::Io; -//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! -//! let mut uart1 = Uart::new(peripherals.UART1, &clocks, io.pins.gpio1, -//! io.pins.gpio2).unwrap(); +//! let system = esp_hal::init(CpuClock::boot_default()); +//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! +//! let mut uart1 = Uart::new( +//! system.peripherals.UART1, +//! &system.clocks, +//! io.pins.gpio1, +//! io.pins.gpio2, +//! ).unwrap(); //! # } //! ``` //! //! The UART controller can be configured to invert the polarity of the pins. -//! This is achived by inverting the desired pins, and then constructing the +//! This is achieved by inverting the desired pins, and then constructing the //! UART instance using the inverted pins. //! //! ## Usage +//! //! The UART driver implements a number of third-party traits, with the //! intention of making the HAL inter-compatible with various device drivers //! from the community. This includes, but is not limited to, the [embedded-hal] @@ -49,12 +58,13 @@ //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::uart::{config::Config, Uart}; -//! use esp_hal::gpio::Io; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # use esp_hal::gpio::Io; +//! # let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); //! # let mut uart1 = Uart::new_with_config( -//! # peripherals.UART1, +//! # system.peripherals.UART1, //! # Config::default(), -//! # &clocks, +//! # &system.clocks, //! # io.pins.gpio1, //! # io.pins.gpio2, //! # ).unwrap(); @@ -67,12 +77,13 @@ //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::uart::{config::Config, Uart}; -//! use esp_hal::gpio::Io; -//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # use esp_hal::gpio::Io; +//! # let system = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); //! # let mut uart1 = Uart::new_with_config( -//! # peripherals.UART1, +//! # system.peripherals.UART1, //! # Config::default(), -//! # &clocks, +//! # &system.clocks, //! # io.pins.gpio1, //! # io.pins.gpio2, //! # ).unwrap(); @@ -90,11 +101,17 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::uart::{config::Config, Uart}; //! use esp_hal::gpio::{AnyPin, Io}; -//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! +//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); //! //! let tx = AnyPin::new_inverted(io.pins.gpio1); //! let rx = AnyPin::new_inverted(io.pins.gpio2); -//! let mut uart1 = Uart::new(peripherals.UART1, &clocks, tx, rx).unwrap(); +//! let mut uart1 = Uart::new( +//! system.peripherals.UART1, +//! &system.clocks, +//! tx, +//! rx, +//! ).unwrap(); //! # } //! ``` //! @@ -103,11 +120,12 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::uart::{config::Config, UartTx, UartRx}; //! use esp_hal::gpio::{AnyPin, Io}; -//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! -//! let tx = UartTx::new(peripherals.UART0, &clocks, +//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! +//! let tx = UartTx::new(system.peripherals.UART0, &system.clocks, //! io.pins.gpio1).unwrap(); -//! let rx = UartRx::new(peripherals.UART1, &clocks, +//! let rx = UartRx::new(system.peripherals.UART1, &system.clocks, //! io.pins.gpio2).unwrap(); //! # } //! ``` @@ -167,7 +185,7 @@ cfg_if::cfg_if! { /// Default RX pin for UART0 on ESP32-C3. /// Corresponds to GPIO20. pub type DefaultRxPin = crate::gpio::Gpio20; - }else if #[cfg(esp32c6)] { + } else if #[cfg(esp32c6)] { /// Default TX pin for UART0 on ESP32-C6. /// Corresponds to GPIO16. pub type DefaultTxPin = crate::gpio::Gpio16; @@ -175,7 +193,7 @@ cfg_if::cfg_if! { /// Default RX pin for UART0 on ESP32-C6. /// Corresponds to GPIO17. pub type DefaultRxPin = crate::gpio::Gpio17; - }else if #[cfg(esp32h2)] { + } else if #[cfg(esp32h2)] { /// Default TX pin for UART0 on ESP32-H2. /// Corresponds to GPIO24. pub type DefaultTxPin = crate::gpio::Gpio24; diff --git a/esp-hal/src/usb_serial_jtag.rs b/esp-hal/src/usb_serial_jtag.rs index 9de1122fd15..808bfdc8e08 100644 --- a/esp-hal/src/usb_serial_jtag.rs +++ b/esp-hal/src/usb_serial_jtag.rs @@ -45,18 +45,22 @@ //! ```rust, no_run #![doc = crate::before_snippet!()] //! use esp_hal::usb_serial_jtag::UsbSerialJtag; -//! let mut usb_serial = UsbSerialJtag::new(peripherals.USB_DEVICE); +//! +//! let system = esp_hal::init(CpuClock::boot_default()); +//! let mut usb_serial = UsbSerialJtag::new(system.peripherals.USB_DEVICE); //! //! // Write bytes out over the USB Serial/JTAG: //! usb_serial.write_bytes(b"Hello, world!").expect("write error!"); -//! } +//! # } //! ``` //! //! ### Splitting the USB Serial/JTAG into TX and RX Components //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::usb_serial_jtag::UsbSerialJtag; -//! let mut usb_serial = UsbSerialJtag::new(peripherals.USB_DEVICE); +//! +//! let system = esp_hal::init(CpuClock::boot_default()); +//! let mut usb_serial = UsbSerialJtag::new(system.peripherals.USB_DEVICE); //! // The USB Serial/JTAG can be split into separate Transmit and Receive //! // components: //! let (mut tx, mut rx) = usb_serial.split(); diff --git a/examples/src/bin/adc.rs b/examples/src/bin/adc.rs index 00d528c17ba..d057ac52627 100644 --- a/examples/src/bin/adc.rs +++ b/examples/src/bin/adc.rs @@ -19,20 +19,19 @@ use esp_backtrace as _; use esp_hal::{ analog::adc::{Adc, AdcConfig, Attenuation}, - clock::ClockControl, delay::Delay, gpio::Io, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/adc_cal.rs b/examples/src/bin/adc_cal.rs index 8b8689e1128..fcb5afc0b51 100644 --- a/examples/src/bin/adc_cal.rs +++ b/examples/src/bin/adc_cal.rs @@ -15,20 +15,19 @@ use esp_backtrace as _; use esp_hal::{ analog::adc::{Adc, AdcConfig, Attenuation}, - clock::ClockControl, delay::Delay, gpio::Io, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/advanced_serial.rs b/examples/src/bin/advanced_serial.rs index 12b4d455151..8575a2d7153 100644 --- a/examples/src/bin/advanced_serial.rs +++ b/examples/src/bin/advanced_serial.rs @@ -13,23 +13,17 @@ #![no_main] use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - delay::Delay, - gpio::Io, - peripherals::Peripherals, - prelude::*, - system::SystemControl, - uart::Uart, -}; +use esp_hal::{delay::Delay, gpio::Io, prelude::*, uart::Uart}; use esp_println::println; use nb::block; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/blinky.rs b/examples/src/bin/blinky.rs index 4509656832f..4afe1fa4f8b 100644 --- a/examples/src/bin/blinky.rs +++ b/examples/src/bin/blinky.rs @@ -10,19 +10,18 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, gpio::{Io, Level, Output}, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); // Set GPIO0 as an output, and set its state high initially. let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/blinky_erased_pins.rs b/examples/src/bin/blinky_erased_pins.rs index d5c6519e065..9a7f219e6e6 100644 --- a/examples/src/bin/blinky_erased_pins.rs +++ b/examples/src/bin/blinky_erased_pins.rs @@ -13,19 +13,18 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, gpio::{AnyInput, AnyOutput, Io, Level, Pull}, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/dac.rs b/examples/src/bin/dac.rs index 7ad9c00226a..16844e69ad7 100644 --- a/examples/src/bin/dac.rs +++ b/examples/src/bin/dac.rs @@ -19,21 +19,15 @@ #![no_main] use esp_backtrace as _; -use esp_hal::{ - analog::dac::Dac, - clock::ClockControl, - delay::Delay, - gpio::Io, - peripherals::Peripherals, - prelude::*, - system::SystemControl, -}; +use esp_hal::{analog::dac::Dac, delay::Delay, gpio::Io, prelude::*}; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/debug_assist.rs b/examples/src/bin/debug_assist.rs index 37a236c2287..99345aeb851 100644 --- a/examples/src/bin/debug_assist.rs +++ b/examples/src/bin/debug_assist.rs @@ -11,22 +11,18 @@ use core::cell::RefCell; use critical_section::Mutex; use esp_backtrace as _; -use esp_hal::{ - assist_debug::DebugAssist, - clock::ClockControl, - peripherals::Peripherals, - prelude::*, - system::SystemControl, -}; +use esp_hal::{assist_debug::DebugAssist, prelude::*}; use esp_println::println; static DA: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let _clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let mut da = DebugAssist::new(peripherals.ASSIST_DEBUG); da.set_interrupt_handler(interrupt_handler); diff --git a/examples/src/bin/dma_extmem2mem.rs b/examples/src/bin/dma_extmem2mem.rs index 63360a776cf..83346f0f0cf 100644 --- a/examples/src/bin/dma_extmem2mem.rs +++ b/examples/src/bin/dma_extmem2mem.rs @@ -9,13 +9,10 @@ use aligned::{Aligned, A64}; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, dma::{Dma, DmaPriority, Mem2Mem}, dma_descriptors_chunk_size, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; use log::{error, info}; extern crate alloc; @@ -65,10 +62,13 @@ fn init_heap(psram: impl esp_hal::peripheral::Peripheral

! { esp_println::logger::init_logger(log::LevelFilter::Info); - let peripherals = Peripherals::take(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); + init_heap(peripherals.PSRAM); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); let delay = Delay::new(&clocks); let mut extram_buffer: &mut [u8] = dma_alloc_buffer!(DATA_SIZE, 64); diff --git a/examples/src/bin/dma_mem2mem.rs b/examples/src/bin/dma_mem2mem.rs index 6374d03c7bb..e4606010ae1 100644 --- a/examples/src/bin/dma_mem2mem.rs +++ b/examples/src/bin/dma_mem2mem.rs @@ -8,13 +8,10 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, dma::{Dma, DmaPriority, Mem2Mem}, dma_buffers, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; use log::{error, info}; @@ -24,9 +21,12 @@ const DATA_SIZE: usize = 1024 * 10; fn main() -> ! { esp_println::logger::init_logger(log::LevelFilter::Info); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); + let delay = Delay::new(&clocks); let (tx_buffer, tx_descriptors, mut rx_buffer, rx_descriptors) = dma_buffers!(DATA_SIZE); diff --git a/examples/src/bin/embassy_hello_world.rs b/examples/src/bin/embassy_hello_world.rs index 9f289cb230a..7eea9c96362 100644 --- a/examples/src/bin/embassy_hello_world.rs +++ b/examples/src/bin/embassy_hello_world.rs @@ -12,12 +12,7 @@ use embassy_executor::Spawner; use embassy_time::{Duration, Timer}; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{prelude::*, timer::timg::TimerGroup}; #[embassy_executor::task] async fn run() { @@ -30,11 +25,13 @@ async fn run() { #[esp_hal_embassy::main] async fn main(spawner: Spawner) { esp_println::logger::init_logger_from_env(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); esp_println::println!("Init!"); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_i2c.rs b/examples/src/bin/embassy_i2c.rs index 9ef50be70d6..a6d703763e8 100644 --- a/examples/src/bin/embassy_i2c.rs +++ b/examples/src/bin/embassy_i2c.rs @@ -19,22 +19,16 @@ use embassy_executor::Spawner; use embassy_time::{Duration, Timer}; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - gpio::Io, - i2c::I2C, - peripherals::Peripherals, - prelude::*, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{gpio::Io, i2c::I2C, prelude::*, timer::timg::TimerGroup}; use lis3dh_async::{Lis3dh, Range, SlaveAddr}; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs b/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs index 1e4482f101d..9537856f413 100644 --- a/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs +++ b/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs @@ -20,21 +20,15 @@ use embassy_executor::Spawner; use embassy_time::{Duration, Timer}; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - gpio::Io, - i2c::I2C, - peripherals::Peripherals, - prelude::*, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{gpio::Io, i2c::I2C, prelude::*, timer::timg::TimerGroup}; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_i2s_read.rs b/examples/src/bin/embassy_i2s_read.rs index edffeec2885..4c2c80d9e18 100644 --- a/examples/src/bin/embassy_i2s_read.rs +++ b/examples/src/bin/embassy_i2s_read.rs @@ -20,14 +20,11 @@ use embassy_executor::Spawner; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, dma::{Dma, DmaPriority}, dma_buffers, gpio::Io, i2s::{asynch::*, DataFormat, I2s, Standard}, - peripherals::Peripherals, prelude::*, - system::SystemControl, timer::timg::TimerGroup, }; use esp_println::println; @@ -35,9 +32,11 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { println!("Init!"); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_i2s_sound.rs b/examples/src/bin/embassy_i2s_sound.rs index bc136a6d6b2..8c54d1ce44e 100644 --- a/examples/src/bin/embassy_i2s_sound.rs +++ b/examples/src/bin/embassy_i2s_sound.rs @@ -34,14 +34,11 @@ use embassy_executor::Spawner; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, dma::{Dma, DmaPriority}, dma_buffers, gpio::Io, i2s::{asynch::*, DataFormat, I2s, Standard}, - peripherals::Peripherals, prelude::*, - system::SystemControl, timer::timg::TimerGroup, }; use esp_println::println; @@ -57,9 +54,11 @@ const SINE: [i16; 64] = [ #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { println!("Init!"); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_multicore.rs b/examples/src/bin/embassy_multicore.rs index 6a150409763..cfc5a704c61 100644 --- a/examples/src/bin/embassy_multicore.rs +++ b/examples/src/bin/embassy_multicore.rs @@ -19,12 +19,9 @@ use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, signal::Signal} use embassy_time::{Duration, Ticker}; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, cpu_control::{CpuControl, Stack}, get_core, gpio::{AnyOutput, Io, Level}, - peripherals::Peripherals, - system::SystemControl, timer::{timg::TimerGroup, ErasedTimer}, }; use esp_hal_embassy::Executor; @@ -54,9 +51,11 @@ async fn control_led( #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/embassy_multicore_interrupt.rs b/examples/src/bin/embassy_multicore_interrupt.rs index 523ed18b522..4bff7915b82 100644 --- a/examples/src/bin/embassy_multicore_interrupt.rs +++ b/examples/src/bin/embassy_multicore_interrupt.rs @@ -18,14 +18,11 @@ use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, signal::Signal} use embassy_time::{Duration, Ticker}; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, cpu_control::{CpuControl, Stack}, get_core, gpio::{AnyOutput, Io, Level}, interrupt::Priority, - peripherals::Peripherals, prelude::*, - system::SystemControl, timer::{timg::TimerGroup, ErasedTimer}, }; use esp_hal_embassy::InterruptExecutor; @@ -74,9 +71,11 @@ async fn enable_disable_led(control: &'static Signal ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/embassy_multiprio.rs b/examples/src/bin/embassy_multiprio.rs index e3802a5d8ac..bdb0672ddda 100644 --- a/examples/src/bin/embassy_multiprio.rs +++ b/examples/src/bin/embassy_multiprio.rs @@ -24,10 +24,7 @@ use embassy_executor::Spawner; use embassy_time::{Duration, Instant, Ticker, Timer}; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, interrupt::Priority, - peripherals::Peripherals, - system::SystemControl, timer::{timg::TimerGroup, ErasedTimer}, }; use esp_hal_embassy::InterruptExecutor; @@ -73,9 +70,12 @@ async fn low_prio_async() { async fn main(low_prio_spawner: Spawner) { esp_println::logger::init_logger_from_env(); println!("Init!"); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); let timer0: ErasedTimer = timg0.timer0.into(); diff --git a/examples/src/bin/embassy_parl_io_rx.rs b/examples/src/bin/embassy_parl_io_rx.rs index 43328f2e037..03393706f98 100644 --- a/examples/src/bin/embassy_parl_io_rx.rs +++ b/examples/src/bin/embassy_parl_io_rx.rs @@ -14,14 +14,11 @@ use embassy_executor::Spawner; use embassy_time::{Duration, Timer}; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, dma::{Dma, DmaPriority}, dma_buffers, gpio::Io, parl_io::{no_clk_pin, BitPackOrder, ParlIoRxOnly, RxFourBits}, - peripherals::Peripherals, prelude::*, - system::SystemControl, timer::systimer::{SystemTimer, Target}, }; use esp_println::println; @@ -29,9 +26,11 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let systimer = SystemTimer::new(peripherals.SYSTIMER).split::(); esp_hal_embassy::init(&clocks, systimer.alarm0); diff --git a/examples/src/bin/embassy_parl_io_tx.rs b/examples/src/bin/embassy_parl_io_tx.rs index ae747156dfc..2b5f96a8814 100644 --- a/examples/src/bin/embassy_parl_io_tx.rs +++ b/examples/src/bin/embassy_parl_io_tx.rs @@ -18,7 +18,6 @@ use embassy_executor::Spawner; use embassy_time::{Duration, Timer}; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, dma::{Dma, DmaPriority}, dma_buffers, gpio::Io, @@ -30,9 +29,7 @@ use esp_hal::{ TxFourBits, TxPinConfigWithValidPin, }, - peripherals::Peripherals, prelude::*, - system::SystemControl, timer::systimer::{SystemTimer, Target}, }; use esp_println::println; @@ -40,9 +37,11 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let systimer = SystemTimer::new(peripherals.SYSTIMER).split::(); esp_hal_embassy::init(&clocks, systimer.alarm0); diff --git a/examples/src/bin/embassy_rmt_rx.rs b/examples/src/bin/embassy_rmt_rx.rs index 16d48dce79c..4c91b896fcc 100644 --- a/examples/src/bin/embassy_rmt_rx.rs +++ b/examples/src/bin/embassy_rmt_rx.rs @@ -13,12 +13,9 @@ use embassy_executor::Spawner; use embassy_time::{Duration, Timer}; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, gpio::{Gpio5, Io, Level, Output}, - peripherals::Peripherals, prelude::*, rmt::{asynch::RxChannelAsync, PulseCode, Rmt, RxChannelConfig, RxChannelCreatorAsync}, - system::SystemControl, timer::timg::TimerGroup, }; use esp_println::{print, println}; @@ -42,9 +39,11 @@ async fn signal_task(mut pin: Output<'static, Gpio5>) { #[esp_hal_embassy::main] async fn main(spawner: Spawner) { println!("Init!"); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_rmt_tx.rs b/examples/src/bin/embassy_rmt_tx.rs index 8c179bcd02a..8b2e43fbf42 100644 --- a/examples/src/bin/embassy_rmt_tx.rs +++ b/examples/src/bin/embassy_rmt_tx.rs @@ -15,12 +15,9 @@ use embassy_executor::Spawner; use embassy_time::{Duration, Timer}; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, gpio::Io, - peripherals::Peripherals, prelude::*, rmt::{asynch::TxChannelAsync, PulseCode, Rmt, TxChannelConfig, TxChannelCreatorAsync}, - system::SystemControl, timer::timg::TimerGroup, }; use esp_println::println; @@ -28,9 +25,12 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { println!("Init!"); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_serial.rs b/examples/src/bin/embassy_serial.rs index 0ea4bdab627..28cbc8d8a5b 100644 --- a/examples/src/bin/embassy_serial.rs +++ b/examples/src/bin/embassy_serial.rs @@ -1,7 +1,7 @@ //! embassy serial //! //! This is an example of running the embassy executor and asynchronously -//! writing to and reading from uart +//! writing to and reading from UART. //% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% FEATURES: async embassy embassy-generic-timers @@ -13,10 +13,8 @@ use embassy_executor::Spawner; use embassy_sync::{blocking_mutex::raw::NoopRawMutex, signal::Signal}; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, gpio::Io, - peripherals::{Peripherals, UART0}, - system::SystemControl, + peripherals::UART0, timer::timg::TimerGroup, uart::{ config::{AtCmdConfig, Config}, @@ -80,9 +78,11 @@ async fn reader( #[esp_hal_embassy::main] async fn main(spawner: Spawner) { esp_println::println!("Init!"); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_spi.rs b/examples/src/bin/embassy_spi.rs index 4a62f2a8450..19f3bf939f5 100644 --- a/examples/src/bin/embassy_spi.rs +++ b/examples/src/bin/embassy_spi.rs @@ -22,23 +22,22 @@ use embassy_executor::Spawner; use embassy_time::{Duration, Timer}; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, dma::*, dma_buffers, gpio::Io, - peripherals::Peripherals, prelude::*, spi::{master::Spi, SpiMode}, - system::SystemControl, timer::timg::TimerGroup, }; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_touch.rs b/examples/src/bin/embassy_touch.rs index eb686243575..33399587ae6 100644 --- a/examples/src/bin/embassy_touch.rs +++ b/examples/src/bin/embassy_touch.rs @@ -17,11 +17,8 @@ use embassy_futures::select::{select, Either}; use embassy_time::{Duration, Timer}; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, gpio::Io, - peripherals::Peripherals, rtc_cntl::Rtc, - system::SystemControl, timer::timg::TimerGroup, touch::{Touch, TouchConfig, TouchPad}, }; @@ -31,9 +28,11 @@ use esp_println::println; async fn main(_spawner: Spawner) { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_twai.rs b/examples/src/bin/embassy_twai.rs index 6c0984d4db6..deb3a40c55d 100644 --- a/examples/src/bin/embassy_twai.rs +++ b/examples/src/bin/embassy_twai.rs @@ -25,11 +25,9 @@ use embassy_sync::{blocking_mutex::raw::NoopRawMutex, channel::Channel}; use embedded_can::{Frame, Id}; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, gpio::Io, interrupt, - peripherals::{self, Peripherals, TWAI0}, - system::SystemControl, + peripherals::{self, TWAI0}, timer::timg::TimerGroup, twai::{self, EspTwaiFrame, TwaiMode, TwaiRx, TwaiTx}, }; @@ -84,9 +82,11 @@ async fn transmitter( #[esp_hal_embassy::main] async fn main(spawner: Spawner) { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_usb_serial.rs b/examples/src/bin/embassy_usb_serial.rs index cd37616c907..670eb07e42e 100644 --- a/examples/src/bin/embassy_usb_serial.rs +++ b/examples/src/bin/embassy_usb_serial.rs @@ -21,23 +21,22 @@ use embassy_usb::{ }; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, gpio::Io, otg_fs::{ asynch::{Config, Driver}, Usb, }, - peripherals::Peripherals, - system::SystemControl, timer::timg::TimerGroup, }; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) -> () { esp_println::println!("Init!"); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_usb_serial_jtag.rs b/examples/src/bin/embassy_usb_serial_jtag.rs index 9cb154f83b7..c537305edc7 100644 --- a/examples/src/bin/embassy_usb_serial_jtag.rs +++ b/examples/src/bin/embassy_usb_serial_jtag.rs @@ -12,9 +12,6 @@ use embassy_executor::Spawner; use embassy_sync::{blocking_mutex::raw::NoopRawMutex, signal::Signal}; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - system::SystemControl, timer::timg::TimerGroup, usb_serial_jtag::{UsbSerialJtag, UsbSerialJtagRx, UsbSerialJtagTx}, Async, @@ -66,9 +63,11 @@ async fn reader( #[esp_hal_embassy::main] async fn main(spawner: Spawner) -> () { esp_println::println!("Init!"); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_wait.rs b/examples/src/bin/embassy_wait.rs index 82e8d3c86b2..a366f2adf9a 100644 --- a/examples/src/bin/embassy_wait.rs +++ b/examples/src/bin/embassy_wait.rs @@ -12,19 +12,18 @@ use embassy_executor::Spawner; use embassy_time::{Duration, Timer}; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, gpio::{Input, Io, Pull}, - peripherals::Peripherals, - system::SystemControl, timer::timg::TimerGroup, }; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/etm_blinky_systimer.rs b/examples/src/bin/etm_blinky_systimer.rs index 89d5ce953ee..bc8f56eacb7 100644 --- a/examples/src/bin/etm_blinky_systimer.rs +++ b/examples/src/bin/etm_blinky_systimer.rs @@ -17,7 +17,6 @@ use esp_hal::{ Level, Pull, }, - peripherals::Peripherals, prelude::*, timer::systimer::{etm::SysTimerEtmEvent, Periodic, SystemTimer}, }; @@ -25,7 +24,7 @@ use fugit::ExtU32; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); + let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); let syst = SystemTimer::new(peripherals.SYSTIMER); let syst_alarms = syst.split::(); diff --git a/examples/src/bin/etm_gpio.rs b/examples/src/bin/etm_gpio.rs index ecced8d304e..0f4f874a59f 100644 --- a/examples/src/bin/etm_gpio.rs +++ b/examples/src/bin/etm_gpio.rs @@ -17,13 +17,12 @@ use esp_hal::{ Level, Pull, }, - peripherals::Peripherals, prelude::*, }; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); + let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let mut led = io.pins.gpio1; diff --git a/examples/src/bin/etm_timer.rs b/examples/src/bin/etm_timer.rs index 802588313a2..5d752415194 100644 --- a/examples/src/bin/etm_timer.rs +++ b/examples/src/bin/etm_timer.rs @@ -11,12 +11,10 @@ use core::cell::RefCell; use critical_section::Mutex; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, etm::Etm, - peripherals::{Peripherals, TIMG0}, + peripherals::TIMG0, prelude::*, - system::SystemControl, timer::timg::{ etm::{TimerEtmEvents, TimerEtmTasks}, Timer, @@ -30,9 +28,11 @@ static TIMER0: Mutex, esp_hal::Blocking>>>> = #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); let timer0 = timg0.timer0; diff --git a/examples/src/bin/gpio_interrupt.rs b/examples/src/bin/gpio_interrupt.rs index 06d730fd301..1d5211d136e 100644 --- a/examples/src/bin/gpio_interrupt.rs +++ b/examples/src/bin/gpio_interrupt.rs @@ -16,13 +16,10 @@ use core::cell::RefCell; use critical_section::Mutex; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, gpio::{self, Event, Input, Io, Level, Output, Pull}, macros::ram, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; cfg_if::cfg_if! { @@ -35,9 +32,11 @@ cfg_if::cfg_if! { #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); // Set GPIO2 as an output, and set its state high initially. let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/hello_rgb.rs b/examples/src/bin/hello_rgb.rs index 5dacba6a05d..125ab2f6ac2 100644 --- a/examples/src/bin/hello_rgb.rs +++ b/examples/src/bin/hello_rgb.rs @@ -25,15 +25,7 @@ #![no_main] use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - delay::Delay, - gpio::Io, - peripherals::Peripherals, - prelude::*, - rmt::Rmt, - system::SystemControl, -}; +use esp_hal::{delay::Delay, gpio::Io, prelude::*, rmt::Rmt}; use esp_hal_smartled::{smartLedBuffer, SmartLedsAdapter}; use smart_leds::{ brightness, @@ -44,9 +36,11 @@ use smart_leds::{ #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/hello_world.rs b/examples/src/bin/hello_world.rs index dc378198900..c844955f4d0 100644 --- a/examples/src/bin/hello_world.rs +++ b/examples/src/bin/hello_world.rs @@ -15,21 +15,15 @@ use core::fmt::Write; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - delay::Delay, - gpio::Io, - peripherals::Peripherals, - prelude::*, - system::SystemControl, - uart::Uart, -}; +use esp_hal::{delay::Delay, gpio::Io, prelude::*, uart::Uart}; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/hmac.rs b/examples/src/bin/hmac.rs index 3df3ef86400..d4c520b2830 100644 --- a/examples/src/bin/hmac.rs +++ b/examples/src/bin/hmac.rs @@ -59,12 +59,9 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, hmac::{Hmac, HmacPurpose, KeyId}, - peripherals::Peripherals, prelude::*, rng::Rng, - system::SystemControl, timer::systimer::SystemTimer, }; use esp_println::println; @@ -76,9 +73,7 @@ type HmacSha256 = HmacSw; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let _clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); let mut rng = Rng::new(peripherals.RNG); diff --git a/examples/src/bin/i2c_bmp180_calibration_data.rs b/examples/src/bin/i2c_bmp180_calibration_data.rs index adf19b1da9c..f80ba7b0c57 100644 --- a/examples/src/bin/i2c_bmp180_calibration_data.rs +++ b/examples/src/bin/i2c_bmp180_calibration_data.rs @@ -12,21 +12,16 @@ #![no_main] use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - gpio::Io, - i2c::I2C, - peripherals::Peripherals, - prelude::*, - system::SystemControl, -}; +use esp_hal::{gpio::Io, i2c::I2C, prelude::*}; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/i2c_display.rs b/examples/src/bin/i2c_display.rs index 7b874872a25..c9332482747 100644 --- a/examples/src/bin/i2c_display.rs +++ b/examples/src/bin/i2c_display.rs @@ -23,22 +23,16 @@ use embedded_graphics::{ text::{Alignment, Text}, }; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - delay::Delay, - gpio::Io, - i2c::I2C, - peripherals::Peripherals, - prelude::*, - system::SystemControl, -}; +use esp_hal::{delay::Delay, gpio::Io, i2c::I2C, prelude::*}; use ssd1306::{prelude::*, I2CDisplayInterface, Ssd1306}; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/i2s_read.rs b/examples/src/bin/i2s_read.rs index 395e1b23257..ecf20f1ff6b 100644 --- a/examples/src/bin/i2s_read.rs +++ b/examples/src/bin/i2s_read.rs @@ -18,22 +18,21 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, dma::{Dma, DmaPriority}, dma_buffers, gpio::Io, i2s::{DataFormat, I2s, I2sReadDma, Standard}, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/i2s_sound.rs b/examples/src/bin/i2s_sound.rs index 991b39d3381..cee33aa8454 100644 --- a/examples/src/bin/i2s_sound.rs +++ b/examples/src/bin/i2s_sound.rs @@ -1,7 +1,7 @@ -//! This shows how to transmit data continously via I2S. +//! This shows how to transmit data continuously via I2S. //! //! Without an additional I2S sink device you can inspect the MCLK, BCLK, WS -//! andDOUT with a logic analyzer. +//! and DOUT with a logic analyzer. //! //! You can also connect e.g. a PCM510x to hear an annoying loud sine tone (full //! scale), so turn down the volume before running this example. @@ -32,14 +32,11 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, dma::{Dma, DmaPriority}, dma_buffers, gpio::Io, i2s::{DataFormat, I2s, I2sWriteDma, Standard}, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; const SINE: [i16; 64] = [ @@ -52,9 +49,11 @@ const SINE: [i16; 64] = [ #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/ieee802154_receive_all_frames.rs b/examples/src/bin/ieee802154_receive_all_frames.rs index 5adb3c0ad0c..63283096c28 100644 --- a/examples/src/bin/ieee802154_receive_all_frames.rs +++ b/examples/src/bin/ieee802154_receive_all_frames.rs @@ -4,13 +4,13 @@ #![no_main] use esp_backtrace as _; -use esp_hal::{peripherals::Peripherals, prelude::*}; +use esp_hal::prelude::*; use esp_ieee802154::*; use esp_println::println; #[entry] fn main() -> ! { - let mut peripherals = Peripherals::take(); + let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); let mut ieee802154 = Ieee802154::new(peripherals.IEEE802154, &mut peripherals.RADIO_CLK); ieee802154.set_config(Config { diff --git a/examples/src/bin/ieee802154_receive_frame.rs b/examples/src/bin/ieee802154_receive_frame.rs index 07e5de3f071..8d8cc9a7a97 100644 --- a/examples/src/bin/ieee802154_receive_frame.rs +++ b/examples/src/bin/ieee802154_receive_frame.rs @@ -4,13 +4,15 @@ #![no_main] use esp_backtrace as _; -use esp_hal::{peripherals::Peripherals, prelude::*}; +use esp_hal::prelude::*; use esp_ieee802154::*; use esp_println::println; #[entry] fn main() -> ! { - let mut peripherals = Peripherals::take(); + let System { + mut peripherals, .. + } = esp_hal::init(CpuClock::boot_default()); let mut ieee802154 = Ieee802154::new(peripherals.IEEE802154, &mut peripherals.RADIO_CLK); ieee802154.set_config(Config { diff --git a/examples/src/bin/ieee802154_send_broadcast_frame.rs b/examples/src/bin/ieee802154_send_broadcast_frame.rs index 070cf8e7983..cb6c3f83e2f 100644 --- a/examples/src/bin/ieee802154_send_broadcast_frame.rs +++ b/examples/src/bin/ieee802154_send_broadcast_frame.rs @@ -4,13 +4,7 @@ #![no_main] use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - delay::Delay, - peripherals::Peripherals, - prelude::*, - system::SystemControl, -}; +use esp_hal::{delay::Delay, prelude::*}; use esp_ieee802154::*; use esp_println::println; use ieee802154::mac::{ @@ -25,9 +19,11 @@ use ieee802154::mac::{ #[entry] fn main() -> ! { - let mut peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + mut peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/ieee802154_send_frame.rs b/examples/src/bin/ieee802154_send_frame.rs index 7992a71694e..0b58de65f59 100644 --- a/examples/src/bin/ieee802154_send_frame.rs +++ b/examples/src/bin/ieee802154_send_frame.rs @@ -4,13 +4,7 @@ #![no_main] use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - delay::Delay, - peripherals::Peripherals, - prelude::*, - system::SystemControl, -}; +use esp_hal::{delay::Delay, prelude::*}; use esp_ieee802154::*; use esp_println::println; use ieee802154::mac::{ @@ -25,9 +19,11 @@ use ieee802154::mac::{ #[entry] fn main() -> ! { - let mut peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + mut peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/ieee802154_sniffer.rs b/examples/src/bin/ieee802154_sniffer.rs index b7e2bb07089..f6adeea22af 100644 --- a/examples/src/bin/ieee802154_sniffer.rs +++ b/examples/src/bin/ieee802154_sniffer.rs @@ -8,23 +8,17 @@ #![no_main] use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - gpio::Io, - peripherals::Peripherals, - prelude::*, - reset::software_reset, - system::SystemControl, - uart::Uart, -}; +use esp_hal::{gpio::Io, prelude::*, reset::software_reset, uart::Uart}; use esp_ieee802154::*; use esp_println::println; #[entry] fn main() -> ! { - let mut peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + mut peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/lcd_cam_ov2640.rs b/examples/src/bin/lcd_cam_ov2640.rs index 07f12f8a1cf..66af3da963e 100644 --- a/examples/src/bin/lcd_cam_ov2640.rs +++ b/examples/src/bin/lcd_cam_ov2640.rs @@ -25,7 +25,6 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, dma::{Dma, DmaPriority}, dma_buffers, @@ -36,18 +35,18 @@ use esp_hal::{ cam::{Camera, RxEightBits}, LcdCam, }, - peripherals::Peripherals, prelude::*, - system::SystemControl, Blocking, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/lcd_i8080.rs b/examples/src/bin/lcd_i8080.rs index b3b02a06292..f332e1c3b48 100644 --- a/examples/src/bin/lcd_i8080.rs +++ b/examples/src/bin/lcd_i8080.rs @@ -23,7 +23,6 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, dma::{Dma, DmaPriority}, dma_buffers, @@ -32,17 +31,17 @@ use esp_hal::{ lcd::i8080::{Config, TxEightBits, I8080}, LcdCam, }, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/ledc.rs b/examples/src/bin/ledc.rs index 94d8dbdb3c9..197e488b972 100644 --- a/examples/src/bin/ledc.rs +++ b/examples/src/bin/ledc.rs @@ -11,7 +11,6 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, gpio::Io, ledc::{ channel::{self, ChannelIFace}, @@ -20,16 +19,16 @@ use esp_hal::{ Ledc, LowSpeed, }, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let led = io.pins.gpio0; diff --git a/examples/src/bin/lp_core_basic.rs b/examples/src/bin/lp_core_basic.rs index 81dc1a7a632..a86affe6ca9 100644 --- a/examples/src/bin/lp_core_basic.rs +++ b/examples/src/bin/lp_core_basic.rs @@ -17,14 +17,13 @@ use esp_backtrace as _; use esp_hal::{ gpio::{lp_io::LowPowerOutput, Io}, lp_core::{LpCore, LpCoreWakeupSource}, - peripherals::Peripherals, prelude::*, }; use esp_println::{print, println}; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); + let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); // configure GPIO 1 as LP output pin let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/lp_core_i2c.rs b/examples/src/bin/lp_core_i2c.rs index b285b4b172d..b384f91a5d1 100644 --- a/examples/src/bin/lp_core_i2c.rs +++ b/examples/src/bin/lp_core_i2c.rs @@ -19,14 +19,13 @@ use esp_hal::{ gpio::{lp_io::LowPowerOutputOpenDrain, Io}, i2c::lp_i2c::LpI2c, lp_core::{LpCore, LpCoreWakeupSource}, - peripherals::Peripherals, prelude::*, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); + let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/lp_core_uart.rs b/examples/src/bin/lp_core_uart.rs index df795db9682..5ca98a3e743 100644 --- a/examples/src/bin/lp_core_uart.rs +++ b/examples/src/bin/lp_core_uart.rs @@ -16,24 +16,23 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, gpio::{ lp_io::{LowPowerInput, LowPowerOutput}, Io, }, lp_core::{LpCore, LpCoreWakeupSource}, - peripherals::Peripherals, prelude::*, - system::SystemControl, uart::{config::Config, lp_uart::LpUart, Uart}, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/mcpwm.rs b/examples/src/bin/mcpwm.rs index f25d932e6c8..aa1c0dc53bf 100644 --- a/examples/src/bin/mcpwm.rs +++ b/examples/src/bin/mcpwm.rs @@ -11,19 +11,18 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, gpio::Io, mcpwm::{operator::PwmPinConfig, timer::PwmWorkingMode, McPwm, PeripheralClockConfig}, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let pin = io.pins.gpio0; diff --git a/examples/src/bin/multicore.rs b/examples/src/bin/multicore.rs index 1d028bdc9b9..da1c30bfcb5 100644 --- a/examples/src/bin/multicore.rs +++ b/examples/src/bin/multicore.rs @@ -13,12 +13,9 @@ use core::{cell::RefCell, ptr::addr_of_mut}; use critical_section::Mutex; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, cpu_control::{CpuControl, Stack}, delay::Delay, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; use esp_println::println; @@ -26,9 +23,11 @@ static mut APP_CORE_STACK: Stack<8192> = Stack::new(); #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/parl_io_rx.rs b/examples/src/bin/parl_io_rx.rs index 0606667f75f..1ac2a674653 100644 --- a/examples/src/bin/parl_io_rx.rs +++ b/examples/src/bin/parl_io_rx.rs @@ -11,23 +11,22 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, dma::{Dma, DmaPriority}, dma_buffers, gpio::Io, parl_io::{no_clk_pin, BitPackOrder, ParlIoRxOnly, RxFourBits}, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/parl_io_tx.rs b/examples/src/bin/parl_io_tx.rs index 60536033a9e..21350a45b96 100644 --- a/examples/src/bin/parl_io_tx.rs +++ b/examples/src/bin/parl_io_tx.rs @@ -15,7 +15,6 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, dma::{Dma, DmaPriority}, dma_buffers, @@ -28,17 +27,17 @@ use esp_hal::{ TxFourBits, TxPinConfigWithValidPin, }, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/pcnt_encoder.rs b/examples/src/bin/pcnt_encoder.rs index 8e22d236b77..c97eb848699 100644 --- a/examples/src/bin/pcnt_encoder.rs +++ b/examples/src/bin/pcnt_encoder.rs @@ -1,6 +1,6 @@ //! PCNT Encoder Demo //! -//! This example decodes a quadrature encoder +//! This example decodes a quadrature encoder. //! //! Since the PCNT units reset to zero when they reach their limits //! we enable an interrupt on the upper and lower limits and @@ -27,7 +27,6 @@ use esp_hal::{ unit, Pcnt, }, - peripherals::Peripherals, prelude::*, }; use esp_println::println; @@ -38,7 +37,7 @@ static VALUE: AtomicI32 = AtomicI32::new(0); #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); + let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/psram_octal.rs b/examples/src/bin/psram_octal.rs index 1916ba4d0c3..9f1be148c08 100644 --- a/examples/src/bin/psram_octal.rs +++ b/examples/src/bin/psram_octal.rs @@ -13,7 +13,7 @@ extern crate alloc; use alloc::{string::String, vec::Vec}; use esp_backtrace as _; -use esp_hal::{peripherals::Peripherals, prelude::*, psram}; +use esp_hal::{prelude::*, psram}; use esp_println::println; #[global_allocator] @@ -30,7 +30,7 @@ fn main() -> ! { #[cfg(debug_assertions)] compile_error!("This example MUST be built in release mode!"); - let peripherals = Peripherals::take(); + let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); psram::init_psram(peripherals.PSRAM); init_psram_heap(); diff --git a/examples/src/bin/psram_quad.rs b/examples/src/bin/psram_quad.rs index 47dfc69ceb8..7a4eb58d2c2 100644 --- a/examples/src/bin/psram_quad.rs +++ b/examples/src/bin/psram_quad.rs @@ -13,13 +13,7 @@ extern crate alloc; use alloc::{string::String, vec::Vec}; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - prelude::*, - psram, - system::SystemControl, -}; +use esp_hal::{clock::ClockControl, prelude::*, psram}; use esp_println::println; #[global_allocator] @@ -36,14 +30,11 @@ fn main() -> ! { #[cfg(debug_assertions)] compile_error!("PSRAM example must be built in release mode!"); - let peripherals = Peripherals::take(); + let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); psram::init_psram(peripherals.PSRAM); init_psram_heap(); - let system = SystemControl::new(peripherals.SYSTEM); - let _clocks = ClockControl::max(system.clock_control).freeze(); - println!("Going to access PSRAM"); let mut large_vec = Vec::::with_capacity(500 * 1024 / 4); diff --git a/examples/src/bin/qspi_flash.rs b/examples/src/bin/qspi_flash.rs index 9c503d8a0ee..7d575a14878 100644 --- a/examples/src/bin/qspi_flash.rs +++ b/examples/src/bin/qspi_flash.rs @@ -29,27 +29,26 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, dma::{Dma, DmaPriority, DmaRxBuf, DmaTxBuf}, dma_buffers, gpio::Io, - peripherals::Peripherals, prelude::*, spi::{ master::{Address, Command, Spi}, SpiDataMode, SpiMode, }, - system::SystemControl, }; use esp_println::{print, println}; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/ram.rs b/examples/src/bin/ram.rs index bd165d99e2d..d5218a644a4 100644 --- a/examples/src/bin/ram.rs +++ b/examples/src/bin/ram.rs @@ -17,15 +17,7 @@ #![no_main] use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - delay::Delay, - macros::ram, - peripherals::Peripherals, - prelude::*, - rtc_cntl::Rtc, - system::SystemControl, -}; +use esp_hal::{delay::Delay, macros::ram, prelude::*, rtc_cntl::Rtc}; use esp_println::println; #[ram(rtc_fast)] @@ -39,9 +31,11 @@ static mut SOME_ZEROED_DATA: [u8; 8] = [0; 8]; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/rmt_rx.rs b/examples/src/bin/rmt_rx.rs index ca9984cec28..6bda14a9988 100644 --- a/examples/src/bin/rmt_rx.rs +++ b/examples/src/bin/rmt_rx.rs @@ -13,13 +13,10 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, gpio::Io, - peripherals::Peripherals, prelude::*, rmt::{PulseCode, Rmt, RxChannel, RxChannelConfig, RxChannelCreator}, - system::SystemControl, }; use esp_println::{print, println}; @@ -27,9 +24,11 @@ const WIDTH: usize = 80; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let mut out = io.pins.gpio5; diff --git a/examples/src/bin/rmt_tx.rs b/examples/src/bin/rmt_tx.rs index d6ef6cf3953..eb1e556c568 100644 --- a/examples/src/bin/rmt_tx.rs +++ b/examples/src/bin/rmt_tx.rs @@ -12,20 +12,19 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, gpio::Io, - peripherals::Peripherals, prelude::*, rmt::{PulseCode, Rmt, TxChannel, TxChannelConfig, TxChannelCreator}, - system::SystemControl, }; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/rng.rs b/examples/src/bin/rng.rs index fc87b7d8fda..2fb85892846 100644 --- a/examples/src/bin/rng.rs +++ b/examples/src/bin/rng.rs @@ -6,12 +6,12 @@ #![no_main] use esp_backtrace as _; -use esp_hal::{peripherals::Peripherals, prelude::*, rng::Rng}; +use esp_hal::{prelude::*, rng::Rng}; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); + let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); let mut rng = Rng::new(peripherals.RNG); // Generate a random word (u32): diff --git a/examples/src/bin/rtc_time.rs b/examples/src/bin/rtc_time.rs index c4e9b876b06..8a30b8aa3d6 100644 --- a/examples/src/bin/rtc_time.rs +++ b/examples/src/bin/rtc_time.rs @@ -6,20 +6,15 @@ #![no_main] use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - delay::Delay, - peripherals::Peripherals, - prelude::*, - rtc_cntl::Rtc, - system::SystemControl, -}; +use esp_hal::{delay::Delay, prelude::*, rtc_cntl::Rtc}; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let rtc = Rtc::new(peripherals.LPWR); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/rtc_watchdog.rs b/examples/src/bin/rtc_watchdog.rs index cddd09dcf8e..47fbee2fe47 100644 --- a/examples/src/bin/rtc_watchdog.rs +++ b/examples/src/bin/rtc_watchdog.rs @@ -1,4 +1,4 @@ -//! This demos the RTC Watchdog Timer (RWDT). +//! This example demonstrates the RTC Watchdog Timer (RWDT). //! //! The RWDT is initially configured to trigger an interrupt after a given //! timeout. Then, upon expiration, the RWDT is restarted and then reconfigured @@ -14,16 +14,17 @@ use core::cell::RefCell; use critical_section::Mutex; use esp_backtrace as _; use esp_hal::{ - peripherals::Peripherals, + interrupt::Priority, prelude::*, rtc_cntl::{Rtc, Rwdt}, }; +use esp_println::println; static RWDT: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); + let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); let mut rtc = Rtc::new(peripherals.LPWR); rtc.set_interrupt_handler(interrupt_handler); @@ -35,16 +36,16 @@ fn main() -> ! { loop {} } -#[handler(priority = esp_hal::interrupt::Priority::min())] +#[handler(priority = Priority::min())] fn interrupt_handler() { critical_section::with(|cs| { - esp_println::println!("RWDT Interrupt"); + println!("RWDT Interrupt"); let mut rwdt = RWDT.borrow_ref_mut(cs); let rwdt = rwdt.as_mut().unwrap(); rwdt.clear_interrupt(); - esp_println::println!("Restarting in 5 seconds..."); + println!("Restarting in 5 seconds..."); rwdt.set_timeout(5000.millis()); rwdt.unlisten(); diff --git a/examples/src/bin/serial_interrupts.rs b/examples/src/bin/serial_interrupts.rs index e0a12904f26..22ebb78e4e9 100644 --- a/examples/src/bin/serial_interrupts.rs +++ b/examples/src/bin/serial_interrupts.rs @@ -12,12 +12,10 @@ use core::{cell::RefCell, fmt::Write}; use critical_section::Mutex; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, gpio::Io, - peripherals::{Peripherals, UART0}, + peripherals::UART0, prelude::*, - system::SystemControl, uart::{ config::{AtCmdConfig, Config}, Uart, @@ -29,9 +27,11 @@ static SERIAL: Mutex>>> = Mutex::new(RefCel #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/sleep_timer.rs b/examples/src/bin/sleep_timer.rs index fa882bd9ac4..19c6eaf2abc 100644 --- a/examples/src/bin/sleep_timer.rs +++ b/examples/src/bin/sleep_timer.rs @@ -9,21 +9,20 @@ use core::time::Duration; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, entry, - peripherals::Peripherals, rtc_cntl::{get_reset_reason, get_wakeup_cause, sleep::TimerWakeupSource, Rtc, SocResetReason}, - system::SystemControl, Cpu, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_ext0.rs b/examples/src/bin/sleep_timer_ext0.rs index b54e646871a..56b47302a8b 100644 --- a/examples/src/bin/sleep_timer_ext0.rs +++ b/examples/src/bin/sleep_timer_ext0.rs @@ -12,11 +12,9 @@ use core::time::Duration; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, entry, gpio::Io, - peripherals::Peripherals, rtc_cntl::{ get_reset_reason, get_wakeup_cause, @@ -24,16 +22,17 @@ use esp_hal::{ Rtc, SocResetReason, }, - system::SystemControl, Cpu, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_ext1.rs b/examples/src/bin/sleep_timer_ext1.rs index 2f702642ffe..e2a5602140e 100644 --- a/examples/src/bin/sleep_timer_ext1.rs +++ b/examples/src/bin/sleep_timer_ext1.rs @@ -12,11 +12,9 @@ use core::time::Duration; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, entry, gpio::{Io, RtcPin}, - peripherals::Peripherals, rtc_cntl::{ get_reset_reason, get_wakeup_cause, @@ -24,16 +22,17 @@ use esp_hal::{ Rtc, SocResetReason, }, - system::SystemControl, Cpu, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_lpio.rs b/examples/src/bin/sleep_timer_lpio.rs index 63c7074f422..cd1b6de2dd6 100644 --- a/examples/src/bin/sleep_timer_lpio.rs +++ b/examples/src/bin/sleep_timer_lpio.rs @@ -13,11 +13,9 @@ use core::time::Duration; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, entry, gpio::{Io, RtcPinWithResistors}, - peripherals::Peripherals, rtc_cntl::{ get_reset_reason, get_wakeup_cause, @@ -25,16 +23,17 @@ use esp_hal::{ Rtc, SocResetReason, }, - system::SystemControl, Cpu, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_rtcio.rs b/examples/src/bin/sleep_timer_rtcio.rs index 6b963f1bee5..74b7e97165c 100644 --- a/examples/src/bin/sleep_timer_rtcio.rs +++ b/examples/src/bin/sleep_timer_rtcio.rs @@ -16,12 +16,10 @@ use core::time::Duration; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, entry, gpio, gpio::Io, - peripherals::Peripherals, rtc_cntl::{ get_reset_reason, get_wakeup_cause, @@ -29,16 +27,17 @@ use esp_hal::{ Rtc, SocResetReason, }, - system::SystemControl, Cpu, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/software_interrupts.rs b/examples/src/bin/software_interrupts.rs index 5fa0f5252b9..b15e233cde4 100644 --- a/examples/src/bin/software_interrupts.rs +++ b/examples/src/bin/software_interrupts.rs @@ -13,13 +13,7 @@ use core::cell::RefCell; use critical_section::Mutex; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - delay::Delay, - peripherals::Peripherals, - prelude::*, - system::{SoftwareInterrupt, SystemControl}, -}; +use esp_hal::{delay::Delay, prelude::*, system::SoftwareInterrupt}; static SWINT0: Mutex>>> = Mutex::new(RefCell::new(None)); static SWINT1: Mutex>>> = Mutex::new(RefCell::new(None)); @@ -28,11 +22,12 @@ static SWINT3: Mutex>>> = Mutex::new(RefCell #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + clocks, + software_interrupt_control: mut sw_int, + .. + } = esp_hal::init(CpuClock::boot_default()); - let mut sw_int = system.software_interrupt_control; critical_section::with(|cs| { sw_int .software_interrupt0 diff --git a/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs b/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs index 8e56ab17b17..e0a01e1c3ce 100644 --- a/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs +++ b/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs @@ -29,25 +29,24 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, gpio::Io, - peripherals::Peripherals, prelude::*, spi::{ master::{Address, Command, HalfDuplexReadWrite, Spi}, SpiDataMode, SpiMode, }, - system::SystemControl, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/spi_loopback.rs b/examples/src/bin/spi_loopback.rs index 6c8432592b2..d9f2d11b598 100644 --- a/examples/src/bin/spi_loopback.rs +++ b/examples/src/bin/spi_loopback.rs @@ -20,21 +20,20 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, gpio::{AnyPin, Io}, - peripherals::Peripherals, prelude::*, spi::{master::Spi, SpiMode}, - system::SystemControl, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/examples/src/bin/spi_loopback_dma.rs b/examples/src/bin/spi_loopback_dma.rs index c277e6fa88d..454a3286ecd 100644 --- a/examples/src/bin/spi_loopback_dma.rs +++ b/examples/src/bin/spi_loopback_dma.rs @@ -34,9 +34,11 @@ use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/examples/src/bin/spi_slave_dma.rs b/examples/src/bin/spi_slave_dma.rs index 6ab99df99a1..2070b000b1d 100644 --- a/examples/src/bin/spi_slave_dma.rs +++ b/examples/src/bin/spi_slave_dma.rs @@ -31,26 +31,25 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, dma::{Dma, DmaPriority}, dma_buffers, gpio::{Gpio4, Gpio5, Gpio8, Gpio9, Input, Io, Level, Output, Pull}, - peripherals::Peripherals, prelude::*, spi::{ slave::{prelude::*, Spi}, SpiMode, }, - system::SystemControl, }; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let slave_sclk = io.pins.gpio0; diff --git a/examples/src/bin/systimer.rs b/examples/src/bin/systimer.rs index cdbf345a96b..05b11715e7f 100644 --- a/examples/src/bin/systimer.rs +++ b/examples/src/bin/systimer.rs @@ -12,11 +12,8 @@ use core::cell::RefCell; use critical_section::Mutex; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, - peripherals::Peripherals, prelude::*, - system::SystemControl, timer::systimer::{ Alarm, FrozenUnit, @@ -50,9 +47,11 @@ static ALARM2: Mutex< #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let systimer = SystemTimer::new(peripherals.SYSTIMER); println!("SYSTIMER Current value = {}", SystemTimer::now()); diff --git a/examples/src/bin/timer_interrupt.rs b/examples/src/bin/timer_interrupt.rs index b22d10aadd4..fe78ef8fb6b 100644 --- a/examples/src/bin/timer_interrupt.rs +++ b/examples/src/bin/timer_interrupt.rs @@ -12,11 +12,9 @@ use core::cell::RefCell; use critical_section::Mutex; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, interrupt::{self, Priority}, - peripherals::{Interrupt, Peripherals, TIMG0}, + peripherals::{Interrupt, TIMG0}, prelude::*, - system::SystemControl, timer::timg::{Timer, Timer0, TimerGroup}, }; @@ -25,9 +23,11 @@ static TIMER0: Mutex, esp_hal::Blocking>>>> = #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); let timer0 = timg0.timer0; diff --git a/examples/src/bin/touch.rs b/examples/src/bin/touch.rs index f7870b07c22..5a7d69e7c99 100644 --- a/examples/src/bin/touch.rs +++ b/examples/src/bin/touch.rs @@ -16,15 +16,12 @@ use core::cell::RefCell; use critical_section::Mutex; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, gpio, gpio::Io, macros::ram, - peripherals::Peripherals, prelude::*, rtc_cntl::Rtc, - system::SystemControl, touch::{Continous, Touch, TouchConfig, TouchPad}, Blocking, }; @@ -51,9 +48,11 @@ fn interrupt_handler() { #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/twai.rs b/examples/src/bin/twai.rs index 374285b3e5c..546b978d3db 100644 --- a/examples/src/bin/twai.rs +++ b/examples/src/bin/twai.rs @@ -26,11 +26,8 @@ const IS_FIRST_SENDER: bool = true; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, gpio::Io, - peripherals::Peripherals, prelude::*, - system::SystemControl, twai::{self, filter::SingleStandardFilter, EspTwaiFrame, StandardId, TwaiMode}, }; use esp_println::println; @@ -38,9 +35,11 @@ use nb::block; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/ulp_riscv_core_basic.rs b/examples/src/bin/ulp_riscv_core_basic.rs index 578e7e6a31d..5477b94d671 100644 --- a/examples/src/bin/ulp_riscv_core_basic.rs +++ b/examples/src/bin/ulp_riscv_core_basic.rs @@ -14,7 +14,6 @@ use esp_backtrace as _; use esp_hal::{ gpio::{rtc_io::*, Io}, - peripherals::Peripherals, prelude::*, ulp_core, }; @@ -22,7 +21,7 @@ use esp_println::{print, println}; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); + let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let pin = LowPowerOutput::new(io.pins.gpio1); diff --git a/examples/src/bin/usb_serial.rs b/examples/src/bin/usb_serial.rs index 4032bc8a0e4..fc3cbde68a7 100644 --- a/examples/src/bin/usb_serial.rs +++ b/examples/src/bin/usb_serial.rs @@ -17,7 +17,6 @@ use esp_backtrace as _; use esp_hal::{ gpio::Io, otg_fs::{Usb, UsbBus}, - peripherals::Peripherals, prelude::*, }; use usb_device::prelude::{UsbDeviceBuilder, UsbVidPid}; @@ -27,7 +26,7 @@ static mut EP_MEMORY: [u32; 1024] = [0; 1024]; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); + let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/usb_serial_jtag.rs b/examples/src/bin/usb_serial_jtag.rs index d87ab1a7978..a79dfbc11be 100644 --- a/examples/src/bin/usb_serial_jtag.rs +++ b/examples/src/bin/usb_serial_jtag.rs @@ -16,24 +16,18 @@ use core::{cell::RefCell, fmt::Write}; use critical_section::Mutex; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - delay::Delay, - peripherals::Peripherals, - prelude::*, - system::SystemControl, - usb_serial_jtag::UsbSerialJtag, - Blocking, -}; +use esp_hal::{delay::Delay, prelude::*, usb_serial_jtag::UsbSerialJtag, Blocking}; static USB_SERIAL: Mutex>>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/watchdog.rs b/examples/src/bin/watchdog.rs index 00ba024813c..9813f620fd7 100644 --- a/examples/src/bin/watchdog.rs +++ b/examples/src/bin/watchdog.rs @@ -9,21 +9,16 @@ #![no_main] use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - delay::Delay, - peripherals::Peripherals, - prelude::*, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{delay::Delay, prelude::*, timer::timg::TimerGroup}; use esp_println::println; #[entry] fn main() -> ! { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/wifi_80211_tx.rs b/examples/src/bin/wifi_80211_tx.rs index d3d70ee062a..59ecc0a05a9 100644 --- a/examples/src/bin/wifi_80211_tx.rs +++ b/examples/src/bin/wifi_80211_tx.rs @@ -12,12 +12,9 @@ use core::marker::PhantomData; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, - peripherals::Peripherals, prelude::*, rng::Rng, - system::SystemControl, timer::{timg::TimerGroup, ErasedTimer, PeriodicTimer}, }; use esp_wifi::{initialize, wifi, EspWifiInitFor}; @@ -38,10 +35,11 @@ const MAC_ADDRESS: [u8; 6] = [0x00, 0x80, 0x41, 0x13, 0x37, 0x42]; fn main() -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/wifi_access_point.rs b/examples/src/bin/wifi_access_point.rs index d9807afa65f..b394e91ca19 100644 --- a/examples/src/bin/wifi_access_point.rs +++ b/examples/src/bin/wifi_access_point.rs @@ -15,14 +15,7 @@ use embedded_io::*; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - prelude::*, - rng::Rng, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{prelude::*, rng::Rng, timer::timg::TimerGroup}; use esp_println::{print, println}; use esp_wifi::{ current_millis, @@ -42,10 +35,11 @@ use smoltcp::iface::SocketStorage; fn main() -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_access_point_with_sta.rs b/examples/src/bin/wifi_access_point_with_sta.rs index 9ca5aaccb41..8e09695fb5d 100644 --- a/examples/src/bin/wifi_access_point_with_sta.rs +++ b/examples/src/bin/wifi_access_point_with_sta.rs @@ -16,14 +16,7 @@ use embedded_io::*; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - prelude::*, - rng::Rng, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{prelude::*, rng::Rng, timer::timg::TimerGroup}; use esp_println::{print, println}; use esp_wifi::{ current_millis, @@ -49,10 +42,11 @@ const PASSWORD: &str = env!("PASSWORD"); fn main() -> ! { esp_println::logger::init_logger(log::LevelFilter::Info); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_bench.rs b/examples/src/bin/wifi_bench.rs index 5427e3b11e6..2f688e4ab06 100644 --- a/examples/src/bin/wifi_bench.rs +++ b/examples/src/bin/wifi_bench.rs @@ -15,15 +15,7 @@ use embedded_io::*; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - delay::Delay, - peripherals::Peripherals, - prelude::*, - rng::Rng, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{delay::Delay, prelude::*, rng::Rng, timer::timg::TimerGroup}; use esp_println::println; use esp_wifi::{ current_millis, @@ -60,10 +52,11 @@ const UPLOAD_DOWNLOAD_PORT: u16 = 4323; fn main() -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let server_address: Ipv4Address = HOST_IP.parse().expect("Invalid HOST_IP address"); diff --git a/examples/src/bin/wifi_ble.rs b/examples/src/bin/wifi_ble.rs index e63ffb2519c..8ac846a5b11 100644 --- a/examples/src/bin/wifi_ble.rs +++ b/examples/src/bin/wifi_ble.rs @@ -24,12 +24,10 @@ use bleps::{ }; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, gpio::{Input, Io, Pull}, peripherals::*, prelude::*, rng::Rng, - system::SystemControl, timer::timg::TimerGroup, }; use esp_println::println; @@ -39,10 +37,11 @@ use esp_wifi::{ble::controller::BleConnector, initialize, EspWifiInitFor}; fn main() -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_coex.rs b/examples/src/bin/wifi_coex.rs index 4f94af99076..084cca7059b 100644 --- a/examples/src/bin/wifi_coex.rs +++ b/examples/src/bin/wifi_coex.rs @@ -26,14 +26,7 @@ use bleps::{ }; use embedded_io::*; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - prelude::*, - rng::Rng, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{prelude::*, rng::Rng, timer::timg::TimerGroup}; use esp_println::{print, println}; use esp_wifi::{ ble::controller::BleConnector, @@ -55,10 +48,11 @@ const PASSWORD: &str = env!("PASSWORD"); fn main() -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_dhcp.rs b/examples/src/bin/wifi_dhcp.rs index 0ae1adb2191..8814172b782 100644 --- a/examples/src/bin/wifi_dhcp.rs +++ b/examples/src/bin/wifi_dhcp.rs @@ -13,14 +13,7 @@ use embedded_io::*; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - prelude::*, - rng::Rng, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{prelude::*, rng::Rng, timer::timg::TimerGroup}; use esp_println::{print, println}; use esp_wifi::{ current_millis, @@ -48,10 +41,11 @@ const PASSWORD: &str = env!("PASSWORD"); fn main() -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_access_point.rs b/examples/src/bin/wifi_embassy_access_point.rs index d030a2f856f..ad33af13cba 100644 --- a/examples/src/bin/wifi_embassy_access_point.rs +++ b/examples/src/bin/wifi_embassy_access_point.rs @@ -27,13 +27,7 @@ use embassy_net::{ }; use embassy_time::{Duration, Timer}; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - rng::Rng, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{rng::Rng, timer::timg::TimerGroup}; use esp_println::{print, println}; use esp_wifi::{ initialize, @@ -63,10 +57,11 @@ macro_rules! mk_static { async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_access_point_with_sta.rs b/examples/src/bin/wifi_embassy_access_point_with_sta.rs index bf49c244394..220707fbb85 100644 --- a/examples/src/bin/wifi_embassy_access_point_with_sta.rs +++ b/examples/src/bin/wifi_embassy_access_point_with_sta.rs @@ -71,10 +71,11 @@ macro_rules! mk_static { async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_bench.rs b/examples/src/bin/wifi_embassy_bench.rs index d4f216d081a..5031f7cb09a 100644 --- a/examples/src/bin/wifi_embassy_bench.rs +++ b/examples/src/bin/wifi_embassy_bench.rs @@ -21,13 +21,7 @@ use embassy_futures::join::join; use embassy_net::{tcp::TcpSocket, Config, Ipv4Address, Stack, StackResources}; use embassy_time::{with_timeout, Duration, Timer}; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - rng::Rng, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{rng::Rng, timer::timg::TimerGroup}; use esp_println::println; use esp_wifi::{ initialize, @@ -73,10 +67,11 @@ static mut TX_BUFFER: [u8; TX_BUFFER_SIZE] = [0; TX_BUFFER_SIZE]; async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let server_address: Ipv4Address = HOST_IP.parse().expect("Invalid HOST_IP address"); diff --git a/examples/src/bin/wifi_embassy_ble.rs b/examples/src/bin/wifi_embassy_ble.rs index 4692d34f167..054926eae4e 100644 --- a/examples/src/bin/wifi_embassy_ble.rs +++ b/examples/src/bin/wifi_embassy_ble.rs @@ -27,11 +27,9 @@ use bleps::{ use embassy_executor::Spawner; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, gpio::{Input, Io, Pull}, peripherals::*, rng::Rng, - system::SystemControl, timer::timg::TimerGroup, }; use esp_println::println; @@ -41,10 +39,11 @@ use esp_wifi::{ble::controller::asynch::BleConnector, initialize, EspWifiInitFor async fn main(_spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); @@ -60,9 +59,9 @@ async fn main(_spawner: Spawner) -> ! { let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { if #[cfg(any(feature = "esp32", feature = "esp32s2", feature = "esp32s3"))] { - let button = Input::new(io.pins.gpio0, Pull::Down); + let button = Input::new(io.pins.gpio0, Pull::Down); } else { - let button = Input::new(io.pins.gpio9, Pull::Down); + let button = Input::new(io.pins.gpio9, Pull::Down); } } diff --git a/examples/src/bin/wifi_embassy_dhcp.rs b/examples/src/bin/wifi_embassy_dhcp.rs index c92ab081cc3..15146591e65 100644 --- a/examples/src/bin/wifi_embassy_dhcp.rs +++ b/examples/src/bin/wifi_embassy_dhcp.rs @@ -17,13 +17,7 @@ use embassy_executor::Spawner; use embassy_net::{tcp::TcpSocket, Config, Ipv4Address, Stack, StackResources}; use embassy_time::{Duration, Timer}; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - rng::Rng, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{rng::Rng, timer::timg::TimerGroup}; use esp_println::println; use esp_wifi::{ initialize, @@ -56,10 +50,11 @@ const PASSWORD: &str = env!("PASSWORD"); async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_esp_now.rs b/examples/src/bin/wifi_embassy_esp_now.rs index cadb06d9532..f93916981a6 100644 --- a/examples/src/bin/wifi_embassy_esp_now.rs +++ b/examples/src/bin/wifi_embassy_esp_now.rs @@ -14,13 +14,7 @@ use embassy_executor::Spawner; use embassy_futures::select::{select, Either}; use embassy_time::{Duration, Ticker}; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - rng::Rng, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{rng::Rng, timer::timg::TimerGroup}; use esp_println::println; use esp_wifi::{ esp_now::{PeerInfo, BROADCAST_ADDRESS}, @@ -32,10 +26,11 @@ use esp_wifi::{ async fn main(_spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_esp_now_duplex.rs b/examples/src/bin/wifi_embassy_esp_now_duplex.rs index 51f7987b730..59c43eaba90 100644 --- a/examples/src/bin/wifi_embassy_esp_now_duplex.rs +++ b/examples/src/bin/wifi_embassy_esp_now_duplex.rs @@ -14,13 +14,7 @@ use embassy_executor::Spawner; use embassy_sync::{blocking_mutex::raw::NoopRawMutex, mutex::Mutex}; use embassy_time::{Duration, Ticker}; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - rng::Rng, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{rng::Rng, timer::timg::TimerGroup}; use esp_println::println; use esp_wifi::{ esp_now::{EspNowManager, EspNowReceiver, EspNowSender, PeerInfo, BROADCAST_ADDRESS}, @@ -42,10 +36,11 @@ macro_rules! mk_static { async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_esp_now.rs b/examples/src/bin/wifi_esp_now.rs index 9dd365c25a1..1e539415d06 100644 --- a/examples/src/bin/wifi_esp_now.rs +++ b/examples/src/bin/wifi_esp_now.rs @@ -9,14 +9,7 @@ #![no_main] use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - prelude::*, - rng::Rng, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{prelude::*, rng::Rng, timer::timg::TimerGroup}; use esp_println::println; use esp_wifi::{ current_millis, @@ -29,10 +22,11 @@ use esp_wifi::{ fn main() -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_sniffer.rs b/examples/src/bin/wifi_sniffer.rs index 90626327507..b8b27b589cb 100644 --- a/examples/src/bin/wifi_sniffer.rs +++ b/examples/src/bin/wifi_sniffer.rs @@ -20,11 +20,8 @@ use critical_section::Mutex; use esp_alloc::heap_allocator; use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, prelude::*, rng::Rng, - system::SystemControl, timer::{timg::TimerGroup, ErasedTimer, PeriodicTimer}, }; use esp_println::println; @@ -37,13 +34,15 @@ static KNOWN_SSIDS: Mutex>> = Mutex::new(RefCell::new(B fn main() -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); + // Create a heap allocator, with 32kB of space. heap_allocator!(32_168); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); - let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); let timer0: ErasedTimer = timg0.timer0.into(); let timer = PeriodicTimer::new(timer0); diff --git a/examples/src/bin/wifi_static_ip.rs b/examples/src/bin/wifi_static_ip.rs index f4d86620cc7..4075c8749c0 100644 --- a/examples/src/bin/wifi_static_ip.rs +++ b/examples/src/bin/wifi_static_ip.rs @@ -14,14 +14,7 @@ use embedded_io::*; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - prelude::*, - rng::Rng, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{prelude::*, rng::Rng, timer::timg::TimerGroup}; use esp_println::{print, println}; use esp_wifi::{ current_millis, @@ -48,10 +41,11 @@ const GATEWAY_IP: &str = env!("GATEWAY_IP"); fn main() -> ! { esp_println::logger::init_logger_from_env(); - let peripherals = Peripherals::take(); - - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::max(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/hil-test/tests/aes.rs b/hil-test/tests/aes.rs index 3ef80264711..ffcc1d23e0c 100644 --- a/hil-test/tests/aes.rs +++ b/hil-test/tests/aes.rs @@ -7,7 +7,7 @@ use esp_hal::{ aes::{Aes, Mode}, - peripherals::Peripherals, + prelude::*, }; use hil_test as _; @@ -17,7 +17,7 @@ struct Context<'a> { impl Context<'_> { pub fn init() -> Self { - let peripherals = Peripherals::take(); + let System { peripherals, .. } = esp_hal::init(CpuClock::max()); let aes = Aes::new(peripherals.AES); Context { aes } diff --git a/hil-test/tests/aes_dma.rs b/hil-test/tests/aes_dma.rs index 63ab5f49edb..67c596dcdae 100644 --- a/hil-test/tests/aes_dma.rs +++ b/hil-test/tests/aes_dma.rs @@ -14,6 +14,7 @@ use esp_hal::{ dma::{Dma, DmaPriority}, dma_buffers, peripherals::Peripherals, + prelude::*, }; use hil_test as _; @@ -27,12 +28,13 @@ mod tests { use super::*; #[init] - fn init() {} + fn init() -> Peripherals { + let system = esp_hal::init(CpuClock::boot_default()); + system.peripherals + } #[test] - fn test_aes_128_dma_encryption() { - let peripherals = Peripherals::take(); - + fn test_aes_128_dma_encryption(peripherals: Peripherals) { let dma = Dma::new(peripherals.DMA); let dma_channel = dma.channel0; @@ -74,9 +76,7 @@ mod tests { } #[test] - fn test_aes_128_dma_decryption() { - let peripherals = Peripherals::take(); - + fn test_aes_128_dma_decryption(peripherals: Peripherals) { let dma = Dma::new(peripherals.DMA); let dma_channel = dma.channel0; @@ -117,9 +117,7 @@ mod tests { } #[test] - fn test_aes_256_dma_encryption() { - let peripherals = Peripherals::take(); - + fn test_aes_256_dma_encryption(peripherals: Peripherals) { let dma = Dma::new(peripherals.DMA); let dma_channel = dma.channel0; @@ -161,9 +159,7 @@ mod tests { } #[test] - fn test_aes_256_dma_decryption() { - let peripherals = Peripherals::take(); - + fn test_aes_256_dma_decryption(peripherals: Peripherals) { let dma = Dma::new(peripherals.DMA); let dma_channel = dma.channel0; diff --git a/hil-test/tests/clock_monitor.rs b/hil-test/tests/clock_monitor.rs index 938108924f5..cfa7e9de3e0 100644 --- a/hil-test/tests/clock_monitor.rs +++ b/hil-test/tests/clock_monitor.rs @@ -5,12 +5,7 @@ #![no_std] #![no_main] -use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - rtc_cntl::Rtc, - system::SystemControl, -}; +use esp_hal::{prelude::*, rtc_cntl::Rtc}; use hil_test as _; struct Context<'a> { @@ -19,11 +14,8 @@ struct Context<'a> { impl Context<'_> { pub fn init() -> Self { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - ClockControl::boot_defaults(system.clock_control).freeze(); - - let rtc = Rtc::new(peripherals.LPWR); + let system = esp_hal::init(CpuClock::boot_default()); + let rtc = Rtc::new(system.peripherals.LPWR); Context { rtc } } diff --git a/hil-test/tests/delay.rs b/hil-test/tests/delay.rs index 96e7adcfb32..8e5854a2c90 100644 --- a/hil-test/tests/delay.rs +++ b/hil-test/tests/delay.rs @@ -6,7 +6,7 @@ #![no_main] use embedded_hal::delay::DelayNs; -use esp_hal::{clock::ClockControl, delay::Delay, peripherals::Peripherals, system::SystemControl}; +use esp_hal::{delay::Delay, prelude::*}; use hil_test as _; struct Context { @@ -15,11 +15,8 @@ struct Context { impl Context { pub fn init() -> Self { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); - - let delay = Delay::new(&clocks); + let system = esp_hal::init(CpuClock::boot_default()); + let delay = Delay::new(&system.clocks); Context { delay } } diff --git a/hil-test/tests/dma_mem2mem.rs b/hil-test/tests/dma_mem2mem.rs index 4609a066b4a..bb960f204bf 100644 --- a/hil-test/tests/dma_mem2mem.rs +++ b/hil-test/tests/dma_mem2mem.rs @@ -6,18 +6,30 @@ #![no_main] use esp_hal::{ - clock::ClockControl, - dma::{Dma, DmaError, DmaPriority, Mem2Mem}, + dma::{Channel, Dma, DmaChannel0, DmaError, DmaPriority, Mem2Mem}, dma_buffers, dma_buffers_chunk_size, dma_descriptors, - peripherals::Peripherals, - system::SystemControl, + prelude::*, + Blocking, }; use hil_test as _; const DATA_SIZE: usize = 1024 * 10; +cfg_if::cfg_if! { + if #[cfg(any(feature = "esp32c2", feature = "esp32c3", feature = "esp32s3"))] { + type DmaPeripheralType = esp_hal::peripherals::SPI2; + } else { + type DmaPeripheralType = esp_hal::peripherals::MEM2MEM1; + } +} + +struct Context { + channel: Channel<'static, DmaChannel0, Blocking>, + dma_peripheral: DmaPeripheralType, +} + #[cfg(test)] #[embedded_test::tests] mod tests { @@ -26,29 +38,37 @@ mod tests { use super::*; #[init] - fn init() {} + fn init() -> Context { + let system = esp_hal::init(CpuClock::boot_default()); - #[test] - fn test_internal_mem2mem() { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let _clocks = ClockControl::boot_defaults(system.clock_control).freeze(); - - let (tx_buffer, tx_descriptors, mut rx_buffer, rx_descriptors) = dma_buffers!(DATA_SIZE); - - let dma = Dma::new(peripherals.DMA); + let dma = Dma::new(system.peripherals.DMA); let channel = dma.channel0.configure(false, DmaPriority::Priority0); cfg_if::cfg_if! { if #[cfg(any(feature = "esp32c2", feature = "esp32c3", feature = "esp32s3"))] { - let dma_peripheral = peripherals.SPI2; + let dma_peripheral = system.peripherals.SPI2; } else { - let dma_peripheral = peripherals.MEM2MEM1; + let dma_peripheral = system.peripherals.MEM2MEM1; } } - let mut mem2mem = - Mem2Mem::new(channel, dma_peripheral, tx_descriptors, rx_descriptors).unwrap(); + Context { + channel, + dma_peripheral, + } + } + + #[test] + fn test_internal_mem2mem(ctx: Context) { + let (tx_buffer, tx_descriptors, mut rx_buffer, rx_descriptors) = dma_buffers!(DATA_SIZE); + + let mut mem2mem = Mem2Mem::new( + ctx.channel, + ctx.dma_peripheral, + tx_descriptors, + rx_descriptors, + ) + .unwrap(); for i in 0..core::mem::size_of_val(tx_buffer) { tx_buffer[i] = (i % 256) as u8; @@ -61,29 +81,15 @@ mod tests { } #[test] - fn test_internal_mem2mem_chunk_size() { + fn test_internal_mem2mem_chunk_size(ctx: Context) { const CHUNK_SIZE: usize = 2048; - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let _clocks = ClockControl::boot_defaults(system.clock_control).freeze(); let (tx_buffer, tx_descriptors, mut rx_buffer, rx_descriptors) = dma_buffers_chunk_size!(DATA_SIZE, CHUNK_SIZE); - let dma = Dma::new(peripherals.DMA); - let channel = dma.channel0.configure(false, DmaPriority::Priority0); - - cfg_if::cfg_if! { - if #[cfg(any(feature = "esp32c2", feature = "esp32c3", feature = "esp32s3"))] { - let dma_peripheral = peripherals.SPI2; - } else { - let dma_peripheral = peripherals.MEM2MEM1; - } - } - let mut mem2mem = Mem2Mem::new_with_chunk_size( - channel, - dma_peripheral, + ctx.channel, + ctx.dma_peripheral, tx_descriptors, rx_descriptors, CHUNK_SIZE, @@ -101,28 +107,13 @@ mod tests { } #[test] - fn test_mem2mem_errors_zero_tx() { + fn test_mem2mem_errors_zero_tx(ctx: Context) { use esp_hal::dma::CHUNK_SIZE; - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let _clocks = ClockControl::boot_defaults(system.clock_control).freeze(); - - let dma = Dma::new(peripherals.DMA); - let channel = dma.channel0.configure(false, DmaPriority::Priority0); - - cfg_if::cfg_if! { - if #[cfg(any(feature = "esp32c2", feature = "esp32c3", feature = "esp32s3"))] { - let dma_peripheral = peripherals.SPI2; - } else { - let dma_peripheral = peripherals.MEM2MEM1; - } - } - let (tx_descriptors, rx_descriptors) = dma_descriptors!(0, 1024); match Mem2Mem::new_with_chunk_size( - channel, - dma_peripheral, + ctx.channel, + ctx.dma_peripheral, tx_descriptors, rx_descriptors, CHUNK_SIZE, @@ -133,28 +124,13 @@ mod tests { } #[test] - fn test_mem2mem_errors_zero_rx() { + fn test_mem2mem_errors_zero_rx(ctx: Context) { use esp_hal::dma::CHUNK_SIZE; - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let _clocks = ClockControl::boot_defaults(system.clock_control).freeze(); - - let dma = Dma::new(peripherals.DMA); - let channel = dma.channel0.configure(false, DmaPriority::Priority0); - - cfg_if::cfg_if! { - if #[cfg(any(feature = "esp32c2", feature = "esp32c3", feature = "esp32s3"))] { - let dma_peripheral = peripherals.SPI2; - } else { - let dma_peripheral = peripherals.MEM2MEM1; - } - } - let (tx_descriptors, rx_descriptors) = dma_descriptors!(1024, 0); match Mem2Mem::new_with_chunk_size( - channel, - dma_peripheral, + ctx.channel, + ctx.dma_peripheral, tx_descriptors, rx_descriptors, CHUNK_SIZE, @@ -165,26 +141,11 @@ mod tests { } #[test] - fn test_mem2mem_errors_chunk_size_too_small() { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let _clocks = ClockControl::boot_defaults(system.clock_control).freeze(); - - let dma = Dma::new(peripherals.DMA); - let channel = dma.channel0.configure(false, DmaPriority::Priority0); - - cfg_if::cfg_if! { - if #[cfg(any(feature = "esp32c2", feature = "esp32c3", feature = "esp32s3"))] { - let dma_peripheral = peripherals.SPI2; - } else { - let dma_peripheral = peripherals.MEM2MEM1; - } - } - + fn test_mem2mem_errors_chunk_size_too_small(ctx: Context) { let (tx_descriptors, rx_descriptors) = dma_descriptors!(1024, 1024); match Mem2Mem::new_with_chunk_size( - channel, - dma_peripheral, + ctx.channel, + ctx.dma_peripheral, tx_descriptors, rx_descriptors, 0, @@ -195,26 +156,11 @@ mod tests { } #[test] - fn test_mem2mem_errors_chunk_size_too_big() { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let _clocks = ClockControl::boot_defaults(system.clock_control).freeze(); - - let dma = Dma::new(peripherals.DMA); - let channel = dma.channel0.configure(false, DmaPriority::Priority0); - - cfg_if::cfg_if! { - if #[cfg(any(feature = "esp32c2", feature = "esp32c3", feature = "esp32s3"))] { - let dma_peripheral = peripherals.SPI2; - } else { - let dma_peripheral = peripherals.MEM2MEM1; - } - } - + fn test_mem2mem_errors_chunk_size_too_big(ctx: Context) { let (tx_descriptors, rx_descriptors) = dma_descriptors!(1024, 1024); match Mem2Mem::new_with_chunk_size( - channel, - dma_peripheral, + ctx.channel, + ctx.dma_peripheral, tx_descriptors, rx_descriptors, 4093, diff --git a/hil-test/tests/ecc.rs b/hil-test/tests/ecc.rs index 2ad0fc923d8..5e4cb64f6e7 100644 --- a/hil-test/tests/ecc.rs +++ b/hil-test/tests/ecc.rs @@ -18,7 +18,7 @@ use elliptic_curve::sec1::ToEncodedPoint; use esp_hal::ecc::WorkMode; use esp_hal::{ ecc::{Ecc, EllipticCurve, Error}, - peripherals::Peripherals, + prelude::*, rng::Rng, Blocking, }; @@ -47,16 +47,6 @@ struct Context<'a> { rng: Rng, } -impl Context<'_> { - pub fn init() -> Self { - let peripherals = Peripherals::take(); - let ecc = Ecc::new(peripherals.ECC); - let rng = Rng::new(peripherals.RNG); - - Context { ecc, rng } - } -} - #[cfg(test)] #[embedded_test::tests] mod tests { @@ -66,7 +56,12 @@ mod tests { #[init] fn init() -> Context<'static> { - Context::init() + let System { peripherals, .. } = esp_hal::init(CpuClock::max()); + + let ecc = Ecc::new(peripherals.ECC); + let rng = Rng::new(peripherals.RNG); + + Context { ecc, rng } } #[test] diff --git a/hil-test/tests/embassy_interrupt_executor.rs b/hil-test/tests/embassy_interrupt_executor.rs index acb6b2c60ba..6080b8b9edc 100644 --- a/hil-test/tests/embassy_interrupt_executor.rs +++ b/hil-test/tests/embassy_interrupt_executor.rs @@ -10,10 +10,9 @@ use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, signal::Signal}; use esp_hal::{ - clock::ClockControl, + clock::CpuClock, interrupt::Priority, - peripherals::Peripherals, - system::{SoftwareInterrupt, SystemControl}, + system::SoftwareInterrupt, timer::timg::TimerGroup, }; use esp_hal_embassy::InterruptExecutor; @@ -38,13 +37,13 @@ async fn interrupt_driven_task(signal: &'static Signal SoftwareInterrupt<1> { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let system = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/hil-test/tests/embassy_timers_executors.rs b/hil-test/tests/embassy_timers_executors.rs index c44605dd7ed..ab1196c677c 100644 --- a/hil-test/tests/embassy_timers_executors.rs +++ b/hil-test/tests/embassy_timers_executors.rs @@ -8,18 +8,15 @@ #![no_main] use embassy_time::{Duration, Ticker, Timer}; -use esp_hal::{ - clock::{ClockControl, Clocks}, - peripherals::Peripherals, - prelude::*, - system::SystemControl, - timer::{timg::TimerGroup, ErasedTimer, OneShotTimer, PeriodicTimer}, -}; #[cfg(not(feature = "esp32"))] use esp_hal::{ interrupt::Priority, timer::systimer::{Alarm, FrozenUnit, Periodic, SystemTimer, Target}, }; +use esp_hal::{ + prelude::*, + timer::{timg::TimerGroup, ErasedTimer, OneShotTimer, PeriodicTimer}, +}; #[cfg(not(feature = "esp32"))] use esp_hal_embassy::InterruptExecutor; use hil_test as _; @@ -109,25 +106,15 @@ mod test_cases { } } -struct Resources { - clocks: Clocks<'static>, - timg0: esp_hal::peripherals::TIMG0, - #[cfg(not(feature = "esp32"))] - systimer: esp_hal::peripherals::SYSTIMER, - software_interrupt_control: esp_hal::system::SoftwareInterruptControl, +fn set_up_embassy_with_timg0(system: System) { + let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); + esp_hal_embassy::init(&system.clocks, timg0.timer0); } -impl Resources { - fn set_up_embassy_with_timg0(self) { - let timg0 = TimerGroup::new(self.timg0, &self.clocks); - esp_hal_embassy::init(&self.clocks, timg0.timer0); - } - - #[cfg(not(feature = "esp32"))] - fn set_up_embassy_with_systimer(self) { - let systimer = SystemTimer::new(self.systimer).split::(); - esp_hal_embassy::init(&self.clocks, systimer.alarm0); - } +#[cfg(not(feature = "esp32"))] +fn set_up_embassy_with_systimer(system: System) { + let systimer = SystemTimer::new(system.peripherals.SYSTIMER).split::(); + esp_hal_embassy::init(&system.clocks, systimer.alarm0); } #[cfg(test)] @@ -137,23 +124,14 @@ mod test { use crate::{test_cases::*, test_helpers::*}; #[init] - fn init() -> Resources { - let peripherals = unsafe { Peripherals::steal() }; - let system = SystemControl::new(peripherals.SYSTEM); - - Resources { - clocks: ClockControl::boot_defaults(system.clock_control).freeze(), - timg0: peripherals.TIMG0, - #[cfg(not(feature = "esp32"))] - systimer: peripherals.SYSTIMER, - software_interrupt_control: system.software_interrupt_control, - } + fn init() -> System { + esp_hal::init(CpuClock::boot_default()) } #[test] #[timeout(3)] - async fn test_one_shot_timg(resources: Resources) { - resources.set_up_embassy_with_timg0(); + async fn test_one_shot_timg(system: System) { + set_up_embassy_with_timg0(system); run_test_one_shot_async().await; } @@ -161,16 +139,16 @@ mod test { #[test] #[timeout(3)] #[cfg(not(feature = "esp32"))] - async fn test_one_shot_systimer(resources: Resources) { - resources.set_up_embassy_with_systimer(); + async fn test_one_shot_systimer(system: System) { + set_up_embassy_with_systimer(system); run_test_one_shot_async().await; } #[test] #[timeout(3)] - fn test_periodic_timg(resources: Resources) { - let timg0 = TimerGroup::new(resources.timg0, &resources.clocks); + fn test_periodic_timg(system: System) { + let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); run_test_periodic_timer(timg0.timer0); } @@ -178,32 +156,32 @@ mod test { #[test] #[timeout(3)] #[cfg(not(feature = "esp32"))] - fn test_periodic_systimer(resources: Resources) { - let systimer = SystemTimer::new(resources.systimer).split::(); + fn test_periodic_systimer(system: System) { + let systimer = SystemTimer::new(system.peripherals.SYSTIMER).split::(); run_test_periodic_timer(systimer.alarm0); } #[test] #[timeout(3)] - fn test_periodic_oneshot_timg(mut resources: Resources) { - let mut timg0 = TimerGroup::new(&mut resources.timg0, &resources.clocks); + fn test_periodic_oneshot_timg(mut system: System) { + let mut timg0 = TimerGroup::new(&mut system.peripherals.TIMG0, &system.clocks); run_test_periodic_timer(&mut timg0.timer0); - let mut timg0 = TimerGroup::new(&mut resources.timg0, &resources.clocks); + let mut timg0 = TimerGroup::new(&mut system.peripherals.TIMG0, &system.clocks); run_test_oneshot_timer(&mut timg0.timer0); } #[test] #[timeout(3)] #[cfg(not(feature = "esp32"))] - fn test_periodic_oneshot_systimer(mut resources: Resources) { - let mut systimer = SystemTimer::new(&mut resources.systimer); + fn test_periodic_oneshot_systimer(mut system: System) { + let mut systimer = SystemTimer::new(&mut system.peripherals.SYSTIMER); let unit = FrozenUnit::new(&mut systimer.unit0); let mut alarm: Alarm<'_, Periodic, _, _, _> = Alarm::new(systimer.comparator0, &unit); run_test_periodic_timer(&mut alarm); - let mut systimer = SystemTimer::new(&mut resources.systimer); + let mut systimer = SystemTimer::new(&mut system.peripherals.SYSTIMER); let unit = FrozenUnit::new(&mut systimer.unit0); let mut alarm: Alarm<'_, Target, _, _, _> = Alarm::new(systimer.comparator0, &unit); run_test_oneshot_timer(&mut alarm); @@ -211,8 +189,8 @@ mod test { #[test] #[timeout(3)] - async fn test_join_timg(resources: Resources) { - resources.set_up_embassy_with_timg0(); + async fn test_join_timg(system: System) { + set_up_embassy_with_timg0(system); run_join_test().await; } @@ -220,8 +198,8 @@ mod test { #[test] #[timeout(3)] #[cfg(not(feature = "esp32"))] - async fn test_join_systimer(resources: Resources) { - resources.set_up_embassy_with_systimer(); + async fn test_join_systimer(system: System) { + set_up_embassy_with_systimer(system); run_join_test().await; } @@ -230,21 +208,21 @@ mod test { #[test] #[timeout(3)] #[cfg(not(feature = "esp32"))] - async fn test_interrupt_executor(resources: Resources) { - let timg0 = TimerGroup::new(resources.timg0, &resources.clocks); + async fn test_interrupt_executor(system: System) { + let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); let timer0: ErasedTimer = timg0.timer0.into(); let timer0 = OneShotTimer::new(timer0); - let systimer = SystemTimer::new(resources.systimer).split::(); + let systimer = SystemTimer::new(system.peripherals.SYSTIMER).split::(); let alarm0: ErasedTimer = systimer.alarm0.into(); let timer1 = OneShotTimer::new(alarm0); let timers = mk_static!([OneShotTimer; 2], [timer0, timer1]); - esp_hal_embassy::init(&resources.clocks, timers); + esp_hal_embassy::init(&system.clocks, timers); let executor = mk_static!( InterruptExecutor<2>, - InterruptExecutor::new(resources.software_interrupt_control.software_interrupt2) + InterruptExecutor::new(system.software_interrupt_control.software_interrupt2) ); #[embassy_executor::task] @@ -283,8 +261,8 @@ mod test { /// Test that timg0 and systimer don't have vastly different tick rates. #[test] #[timeout(3)] - async fn tick_test_timer_tick_rates(resources: Resources) { - resources.set_up_embassy_with_timg0(); + async fn tick_test_timer_tick_rates(system: System) { + set_up_embassy_with_timg0(system); // We are retrying 5 times because probe-rs polling RTT may introduce some // jitter. diff --git a/hil-test/tests/get_time.rs b/hil-test/tests/get_time.rs index 31afab56ed5..5511c564825 100644 --- a/hil-test/tests/get_time.rs +++ b/hil-test/tests/get_time.rs @@ -7,7 +7,7 @@ #[cfg(esp32)] use esp_hal::clock::Clocks; -use esp_hal::{clock::ClockControl, delay::Delay, peripherals::Peripherals, system::SystemControl}; +use esp_hal::{delay::Delay, prelude::*, system::SystemControl}; use hil_test as _; struct Context { @@ -17,19 +17,7 @@ struct Context { } impl Context { - pub fn init() -> Self { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); - - let delay = Delay::new(&clocks); - - Context { - delay, - #[cfg(esp32)] - clocks, - } - } + pub fn init() -> Self {} } fn time_moves_forward_during(ctx: Context, f: F) { @@ -47,7 +35,15 @@ mod tests { #[init] fn init() -> Context { - Context::init() + let system = esp_hal::init(CpuClock::boot_default()); + + let delay = Delay::new(&system.clocks); + + Context { + delay, + #[cfg(esp32)] + clocks: system.clocks, + } } #[test] diff --git a/hil-test/tests/gpio.rs b/hil-test/tests/gpio.rs index 0e989708d66..4281e4cfc8c 100644 --- a/hil-test/tests/gpio.rs +++ b/hil-test/tests/gpio.rs @@ -1,8 +1,8 @@ //! GPIO Test //! //! Folowing pins are used: -//! GPIO2 -//! GPIO3 +//! - GPIO2 +//! - GPIO3 //% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% FEATURES: generic-queue @@ -14,12 +14,10 @@ use core::cell::RefCell; use critical_section::Mutex; use esp_hal::{ - clock::ClockControl, delay::Delay, gpio::{AnyPin, Gpio2, Gpio3, GpioPin, Input, Io, Level, Output, Pull}, macros::handler, - peripherals::Peripherals, - system::SystemControl, + prelude::*, timer::timg::TimerGroup, InterruptConfigurable, }; @@ -36,17 +34,15 @@ struct Context<'d> { impl<'d> Context<'d> { pub fn init() -> Self { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let system = esp_hal::init(CpuClock::boot_default()); - let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); + let mut io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); io.set_interrupt_handler(interrupt_handler); - let delay = Delay::new(&clocks); + let delay = Delay::new(&system.clocks); - let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); - esp_hal_embassy::init(&clocks, timg0.timer0); + let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); + esp_hal_embassy::init(&system.clocks, timg0.timer0); Context { io2: Input::new(io.pins.gpio2, Pull::Down), diff --git a/hil-test/tests/i2s.rs b/hil-test/tests/i2s.rs index 4aa833f50c1..fd282ea3098 100644 --- a/hil-test/tests/i2s.rs +++ b/hil-test/tests/i2s.rs @@ -11,16 +11,13 @@ #![no_main] use esp_hal::{ - clock::ClockControl, delay::Delay, dma::{Dma, DmaPriority}, dma_buffers, gpio::Io, i2s::{DataFormat, I2s, I2sReadDma, I2sWriteDma, Standard}, peripheral::Peripheral, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; use hil_test as _; @@ -52,17 +49,14 @@ impl Iterator for SampleSource { #[cfg(test)] #[embedded_test::tests] mod tests { - use super::*; - #[init] - fn init() {} - #[test] fn test_i2s_loopback() { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let system = esp_hal::init(CpuClock::boot_default()); + + let peripherals = system.peripherals; + let clocks = system.clocks; let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/i2s_async.rs b/hil-test/tests/i2s_async.rs index ba5175e988f..ead6e40c572 100644 --- a/hil-test/tests/i2s_async.rs +++ b/hil-test/tests/i2s_async.rs @@ -12,14 +12,12 @@ #![no_main] use esp_hal::{ - clock::ClockControl, dma::{Dma, DmaChannel0, DmaPriority}, gpio::Io, i2s::{asynch::*, DataFormat, I2s, I2sTx, Standard}, peripheral::Peripheral, - peripherals::{Peripherals, I2S0}, + peripherals::I2S0, prelude::*, - system::SystemControl, Async, }; use hil_test as _; @@ -83,16 +81,14 @@ mod tests { use super::*; - #[init] - async fn init() {} - #[test] async fn test_i2s_loopback() { let spawner = embassy_executor::Spawner::for_current_executor().await; - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let system = esp_hal::init(CpuClock::boot_default()); + + let peripherals = system.peripherals; + let clocks = system.clocks; let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/interrupt.rs b/hil-test/tests/interrupt.rs index 105f01290be..37fc5eb0e2a 100644 --- a/hil-test/tests/interrupt.rs +++ b/hil-test/tests/interrupt.rs @@ -11,10 +11,10 @@ use core::{arch::asm, cell::RefCell}; use critical_section::Mutex; use esp_hal::{ - clock::ClockControl, interrupt::{self, *}, - peripherals::{Interrupt, Peripherals}, - system::{SoftwareInterrupt, SystemControl}, + peripherals::Interrupt, + prelude::*, + system::SoftwareInterrupt, }; use hil_test as _; @@ -27,7 +27,11 @@ struct Context { impl Context { pub fn init() -> Self { - let peripherals = Peripherals::take(); + let System { + peripherals, + software_interrupt_control: sw_int, + .. + } = esp_hal::init(CpuClock::max()); cfg_if::cfg_if! { if #[cfg(any(feature = "esp32c6", feature = "esp32h2"))] { @@ -39,11 +43,6 @@ impl Context { let sw0_trigger_addr = cpu_intr.cpu_intr_from_cpu_0() as *const _ as u32; - let system = SystemControl::new(peripherals.SYSTEM); - let _clocks = ClockControl::max(system.clock_control).freeze(); - - let sw_int = system.software_interrupt_control; - critical_section::with(|cs| { SWINT0 .borrow_ref_mut(cs) diff --git a/hil-test/tests/lcd_cam_i8080.rs b/hil-test/tests/lcd_cam_i8080.rs index 42563ad107e..22d1238066c 100644 --- a/hil-test/tests/lcd_cam_i8080.rs +++ b/hil-test/tests/lcd_cam_i8080.rs @@ -6,20 +6,15 @@ #![no_main] use esp_hal::{ - clock::{ClockControl, Clocks}, + clock::Clocks, dma::{Dma, DmaDescriptor, DmaPriority}, dma_buffers, gpio::DummyPin, lcd_cam::{ - lcd::{ - i8080, - i8080::{Command, TxEightBits, I8080}, - }, + lcd::i8080::{self, Command, TxEightBits, I8080}, LcdCam, }, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; use hil_test as _; @@ -33,16 +28,23 @@ struct Context<'d> { tx_descriptors: &'static mut [DmaDescriptor], } -impl<'d> Context<'d> { - pub fn init() -> Self { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); +#[cfg(test)] +#[embedded_test::tests] +mod tests { + use super::*; + + #[init] + fn init() -> Context<'static> { + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let dma = Dma::new(peripherals.DMA); let lcd_cam = LcdCam::new(peripherals.LCD_CAM); let (tx_buffer, tx_descriptors, _, _) = dma_buffers!(DATA_SIZE, 0); - Self { + Context { lcd_cam, clocks, dma, @@ -50,17 +52,6 @@ impl<'d> Context<'d> { tx_descriptors, } } -} - -#[cfg(test)] -#[embedded_test::tests] -mod tests { - use super::*; - - #[init] - fn init() -> Context<'static> { - Context::init() - } #[test] fn test_i8080_8bit(ctx: Context<'static>) { diff --git a/hil-test/tests/lcd_cam_i8080_async.rs b/hil-test/tests/lcd_cam_i8080_async.rs index 6b89fb767b3..9d82a64dc0d 100644 --- a/hil-test/tests/lcd_cam_i8080_async.rs +++ b/hil-test/tests/lcd_cam_i8080_async.rs @@ -7,7 +7,7 @@ #![no_main] use esp_hal::{ - clock::{ClockControl, Clocks}, + clock::Clocks, dma::{Dma, DmaDescriptor, DmaPriority}, dma_buffers, gpio::DummyPin, @@ -18,9 +18,7 @@ use esp_hal::{ }, LcdCam, }, - peripherals::Peripherals, prelude::*, - system::SystemControl, }; use hil_test as _; @@ -34,16 +32,24 @@ struct Context<'d> { tx_descriptors: &'static mut [DmaDescriptor], } -impl<'d> Context<'d> { - pub fn init() -> Self { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); +#[cfg(test)] +#[embedded_test::tests(executor = esp_hal_embassy::Executor::new())] +mod tests { + use super::*; + + #[init] + async fn init() -> Context<'static> { + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); + let dma = Dma::new(peripherals.DMA); let lcd_cam = LcdCam::new_async(peripherals.LCD_CAM); let (tx_buffer, tx_descriptors, _, _) = dma_buffers!(DATA_SIZE, 0); - Self { + Context { lcd_cam, clocks, dma, @@ -51,17 +57,6 @@ impl<'d> Context<'d> { tx_descriptors, } } -} - -#[cfg(test)] -#[embedded_test::tests(executor = esp_hal_embassy::Executor::new())] -mod tests { - use super::*; - - #[init] - async fn init() -> Context<'static> { - Context::init() - } #[test] async fn test_i8080_8bit(ctx: Context<'static>) { diff --git a/hil-test/tests/pcnt.rs b/hil-test/tests/pcnt.rs index ec25dff4479..0ae11fb2d62 100644 --- a/hil-test/tests/pcnt.rs +++ b/hil-test/tests/pcnt.rs @@ -7,7 +7,15 @@ #![no_std] #![no_main] -use esp_hal::{delay::Delay, gpio::GpioPin, pcnt::Pcnt}; +use esp_hal::{ + delay::Delay, + gpio::{GpioPin, Io, Level, Output, Pull}, + pcnt::{ + channel::{EdgeMode, PcntInputConfig, PcntSource}, + Pcnt, + }, + prelude::*, +}; use hil_test as _; struct Context<'d> { @@ -20,22 +28,15 @@ struct Context<'d> { #[cfg(test)] #[embedded_test::tests] mod tests { - use esp_hal::{ - clock::ClockControl, - delay::Delay, - gpio::{Io, Level, Output, Pull}, - pcnt::channel::{EdgeMode, PcntInputConfig, PcntSource}, - peripherals::Peripherals, - system::SystemControl, - }; - use super::*; #[init] fn init() -> Context<'static> { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/rmt.rs b/hil-test/tests/rmt.rs index 30359b3707e..5595651a15b 100644 --- a/hil-test/tests/rmt.rs +++ b/hil-test/tests/rmt.rs @@ -8,12 +8,9 @@ #![no_main] use esp_hal::{ - clock::ClockControl, gpio::Io, - peripherals::Peripherals, prelude::*, rmt::{PulseCode, Rmt, RxChannel, RxChannelConfig, TxChannel, TxChannelConfig}, - system::SystemControl, }; use hil_test as _; @@ -28,9 +25,11 @@ mod tests { #[test] #[timeout(1)] fn rmt_loopback() { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/rsa.rs b/hil-test/tests/rsa.rs index c102dd025a5..ae73767d45a 100644 --- a/hil-test/tests/rsa.rs +++ b/hil-test/tests/rsa.rs @@ -7,7 +7,6 @@ use crypto_bigint::{Uint, U1024, U512}; use esp_hal::{ - peripherals::Peripherals, prelude::*, rsa::{ operand_sizes::*, @@ -58,7 +57,7 @@ mod tests { #[init] fn init() -> Context<'static> { - let peripherals = Peripherals::take(); + let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); let mut rsa = Rsa::new(peripherals.RSA); nb::block!(rsa.ready()).unwrap(); diff --git a/hil-test/tests/sha.rs b/hil-test/tests/sha.rs index bdaf699d7b7..50047f21680 100644 --- a/hil-test/tests/sha.rs +++ b/hil-test/tests/sha.rs @@ -13,12 +13,10 @@ use esp_hal::sha::{Sha384, Sha512}; #[cfg(any(feature = "esp32s2", feature = "esp32s3"))] use esp_hal::sha::{Sha512_224, Sha512_256}; use esp_hal::{ - clock::ClockControl, peripherals::Peripherals, prelude::*, rng::Rng, sha::{Sha, Sha1, Sha256}, - system::SystemControl, Blocking, }; use hil_test as _; @@ -165,14 +163,12 @@ mod tests { #[init] fn init() -> Rng { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); cfg_if::cfg_if! { if #[cfg(feature = "esp32")] { // FIXME: max speed fails...? - let _clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); } else { - let _clocks = ClockControl::max(system.clock_control).freeze(); + let System { peripherals, .. } = esp_hal::init(CpuClock::max()); } } diff --git a/hil-test/tests/spi_full_duplex.rs b/hil-test/tests/spi_full_duplex.rs index 0502f0c1da2..89515a63de9 100644 --- a/hil-test/tests/spi_full_duplex.rs +++ b/hil-test/tests/spi_full_duplex.rs @@ -15,12 +15,9 @@ use embedded_hal::spi::SpiBus; use esp_hal::{ - clock::ClockControl, gpio::Io, - peripherals::Peripherals, prelude::*, spi::{master::Spi, FullDuplexMode, SpiMode}, - system::SystemControl, }; use hil_test as _; @@ -37,9 +34,11 @@ mod tests { #[init] fn init() -> Context { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/spi_full_duplex_dma.rs b/hil-test/tests/spi_full_duplex_dma.rs index 7810c4de7b2..d7f3e07a71c 100644 --- a/hil-test/tests/spi_full_duplex_dma.rs +++ b/hil-test/tests/spi_full_duplex_dma.rs @@ -55,9 +55,11 @@ mod tests { #[init] fn init() -> Context { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/spi_full_duplex_dma_async.rs b/hil-test/tests/spi_full_duplex_dma_async.rs index 3dd9bc45998..ac91128dc52 100644 --- a/hil-test/tests/spi_full_duplex_dma_async.rs +++ b/hil-test/tests/spi_full_duplex_dma_async.rs @@ -1,6 +1,6 @@ //! SPI Full Duplex DMA Test //! -//! Folowing pins are used: +//! Following pins are used: //! SCLK GPIO0 //! MOSI GPIO3 //! MISO GPIO6 @@ -72,9 +72,11 @@ mod tests { #[init] fn init() -> Context { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let pcnt = Pcnt::new(peripherals.PCNT); diff --git a/hil-test/tests/spi_half_duplex_read.rs b/hil-test/tests/spi_half_duplex_read.rs index eda40ba5e55..e30be14a97e 100644 --- a/hil-test/tests/spi_half_duplex_read.rs +++ b/hil-test/tests/spi_half_duplex_read.rs @@ -56,9 +56,11 @@ mod tests { #[init] fn init() -> Context { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/spi_half_duplex_write.rs b/hil-test/tests/spi_half_duplex_write.rs index 196bed37716..daa88004233 100644 --- a/hil-test/tests/spi_half_duplex_write.rs +++ b/hil-test/tests/spi_half_duplex_write.rs @@ -65,9 +65,11 @@ mod tests { #[init] fn init() -> Context { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/systimer.rs b/hil-test/tests/systimer.rs index e8360539d85..3b0116c48ca 100644 --- a/hil-test/tests/systimer.rs +++ b/hil-test/tests/systimer.rs @@ -11,11 +11,9 @@ use core::cell::RefCell; use critical_section::Mutex; use embedded_hal::delay::DelayNs; use esp_hal::{ - clock::{ClockControl, Clocks}, + clock::Clocks, delay::Delay, - peripherals::Peripherals, prelude::*, - system::SystemControl, timer::systimer::{ Alarm, FrozenUnit, @@ -46,27 +44,6 @@ struct Context { clocks: Clocks<'static>, } -impl Context { - pub fn init() -> Self { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); - - let systimer = SystemTimer::new(peripherals.SYSTIMER); - static UNIT0: StaticCell> = StaticCell::new(); - - let unit0 = UNIT0.init(systimer.unit0); - let frozen_unit = FrozenUnit::new(unit0); - - Context { - clocks, - unit: frozen_unit, - comparator0: systimer.comparator0, - comparator1: systimer.comparator1, - } - } -} - #[handler(priority = esp_hal::interrupt::Priority::min())] fn pass_test_if_called() { critical_section::with(|cs| { @@ -127,7 +104,24 @@ mod tests { #[init] fn init() -> Context { - Context::init() + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); + + let systimer = SystemTimer::new(peripherals.SYSTIMER); + static UNIT0: StaticCell> = StaticCell::new(); + + let unit0 = UNIT0.init(systimer.unit0); + let frozen_unit = FrozenUnit::new(unit0); + + Context { + clocks, + unit: frozen_unit, + comparator0: systimer.comparator0, + comparator1: systimer.comparator1, + } } #[test] diff --git a/hil-test/tests/twai.rs b/hil-test/tests/twai.rs index c410c9fd590..efc6df74962 100644 --- a/hil-test/tests/twai.rs +++ b/hil-test/tests/twai.rs @@ -13,11 +13,9 @@ use embedded_hal_02::can::Frame; use esp_hal::{ - clock::ClockControl, gpio::Io, - peripherals::{Peripherals, TWAI0}, + peripherals::TWAI0, prelude::*, - system::SystemControl, twai::{self, filter::SingleStandardFilter, EspTwaiFrame, StandardId, TwaiMode}, Blocking, }; @@ -28,25 +26,32 @@ struct Context { twai: twai::Twai<'static, TWAI0, Blocking>, } -impl Context { - pub fn init() -> Self { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); +#[cfg(test)] +#[embedded_test::tests] +mod tests { + use defmt::assert_eq; + + use super::*; + + #[init] + fn init() -> Context { + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let can_tx_pin = io.pins.gpio2; let can_rx_pin = io.pins.gpio3; - const CAN_BAUDRATE: twai::BaudRate = twai::BaudRate::B1000K; - let mut config = twai::TwaiConfiguration::new( peripherals.TWAI0, can_tx_pin, can_rx_pin, &clocks, - CAN_BAUDRATE, + twai::BaudRate::B1000K, TwaiMode::SelfTest, ); @@ -58,19 +63,6 @@ impl Context { Context { twai } } -} - -#[cfg(test)] -#[embedded_test::tests] -mod tests { - use defmt::assert_eq; - - use super::*; - - #[init] - fn init() -> Context { - Context::init() - } #[test] #[timeout(3)] diff --git a/hil-test/tests/uart.rs b/hil-test/tests/uart.rs index cb87373ffad..06fc2f122fa 100644 --- a/hil-test/tests/uart.rs +++ b/hil-test/tests/uart.rs @@ -13,11 +13,10 @@ use embedded_hal_02::serial::{Read, Write}; use esp_hal::{ - clock::{ClockControl, Clocks}, + clock::Clocks, gpio::Io, - peripherals::{Peripherals, UART1}, + peripherals::UART1, prelude::*, - system::SystemControl, uart::{ClockSource, Uart}, Blocking, }; @@ -29,20 +28,6 @@ struct Context { uart: Uart<'static, UART1, Blocking>, } -impl Context { - pub fn init() -> Self { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); - - let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); - - let uart = Uart::new(peripherals.UART1, &clocks, io.pins.gpio2, io.pins.gpio3).unwrap(); - - Context { clocks, uart } - } -} - #[cfg(test)] #[embedded_test::tests] mod tests { @@ -52,7 +37,17 @@ mod tests { #[init] fn init() -> Context { - Context::init() + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); + + let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); + + let uart = Uart::new(peripherals.UART1, &clocks, io.pins.gpio2, io.pins.gpio3).unwrap(); + + Context { clocks, uart } } #[test] diff --git a/hil-test/tests/uart_async.rs b/hil-test/tests/uart_async.rs index b3cb05612f2..43e3c632fdb 100644 --- a/hil-test/tests/uart_async.rs +++ b/hil-test/tests/uart_async.rs @@ -12,34 +12,13 @@ #![no_std] #![no_main] -use esp_hal::{ - clock::ClockControl, - gpio::Io, - peripherals::{Peripherals, UART0}, - system::SystemControl, - uart::Uart, - Async, -}; +use esp_hal::{gpio::Io, peripherals::UART0, prelude::*, uart::Uart, Async}; use hil_test as _; struct Context { uart: Uart<'static, UART0, Async>, } -impl Context { - pub fn init() -> Self { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); - let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); - - let uart = - Uart::new_async(peripherals.UART0, &clocks, io.pins.gpio2, io.pins.gpio3).unwrap(); - - Context { uart } - } -} - #[cfg(test)] #[embedded_test::tests(executor = esp_hal_embassy::Executor::new())] mod tests { @@ -49,7 +28,18 @@ mod tests { #[init] async fn init() -> Context { - Context::init() + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); + + let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); + + let uart = + Uart::new_async(peripherals.UART0, &clocks, io.pins.gpio2, io.pins.gpio3).unwrap(); + + Context { uart } } #[test] diff --git a/hil-test/tests/uart_tx_rx.rs b/hil-test/tests/uart_tx_rx.rs index 67a56460663..a9b2f494f06 100644 --- a/hil-test/tests/uart_tx_rx.rs +++ b/hil-test/tests/uart_tx_rx.rs @@ -12,11 +12,9 @@ #![no_main] use esp_hal::{ - clock::ClockControl, gpio::Io, - peripherals::{Peripherals, UART0, UART1}, + peripherals::{UART0, UART1}, prelude::*, - system::SystemControl, uart::{UartRx, UartTx}, Blocking, }; @@ -28,21 +26,6 @@ struct Context { rx: UartRx<'static, UART1, Blocking>, } -impl Context { - pub fn init() -> Self { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); - - let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); - - let tx = UartTx::new(peripherals.UART0, &clocks, io.pins.gpio2).unwrap(); - let rx = UartRx::new(peripherals.UART1, &clocks, io.pins.gpio3).unwrap(); - - Context { tx, rx } - } -} - #[cfg(test)] #[embedded_test::tests] mod tests { @@ -52,7 +35,18 @@ mod tests { #[init] fn init() -> Context { - Context::init() + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); + + let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); + + let tx = UartTx::new(peripherals.UART0, &clocks, io.pins.gpio2).unwrap(); + let rx = UartRx::new(peripherals.UART1, &clocks, io.pins.gpio3).unwrap(); + + Context { tx, rx } } #[test] diff --git a/hil-test/tests/uart_tx_rx_async.rs b/hil-test/tests/uart_tx_rx_async.rs index 627cab28aa0..01aedbbf661 100644 --- a/hil-test/tests/uart_tx_rx_async.rs +++ b/hil-test/tests/uart_tx_rx_async.rs @@ -13,10 +13,9 @@ #![no_main] use esp_hal::{ - clock::ClockControl, gpio::Io, - peripherals::{Peripherals, UART0, UART1}, - system::SystemControl, + peripherals::{UART0, UART1}, + prelude::*, uart::{UartRx, UartTx}, Async, }; @@ -27,21 +26,6 @@ struct Context { rx: UartRx<'static, UART1, Async>, } -impl Context { - pub fn init() -> Self { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); - - let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); - - let tx = UartTx::new_async(peripherals.UART0, &clocks, io.pins.gpio2).unwrap(); - let rx = UartRx::new_async(peripherals.UART1, &clocks, io.pins.gpio3).unwrap(); - - Context { tx, rx } - } -} - #[cfg(test)] #[embedded_test::tests(executor = esp_hal_embassy::Executor::new())] mod tests { @@ -51,7 +35,18 @@ mod tests { #[init] async fn init() -> Context { - Context::init() + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); + + let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); + + let tx = UartTx::new_async(peripherals.UART0, &clocks, io.pins.gpio2).unwrap(); + let rx = UartRx::new_async(peripherals.UART1, &clocks, io.pins.gpio3).unwrap(); + + Context { tx, rx } } #[test] diff --git a/hil-test/tests/usb_serial_jtag.rs b/hil-test/tests/usb_serial_jtag.rs index f343f6023df..e4a582ba0c4 100644 --- a/hil-test/tests/usb_serial_jtag.rs +++ b/hil-test/tests/usb_serial_jtag.rs @@ -8,20 +8,16 @@ #[cfg(test)] #[embedded_test::tests] mod tests { - use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - system::SystemControl, - timer::timg::TimerGroup, - usb_serial_jtag::UsbSerialJtag, - }; + use esp_hal::{prelude::*, timer::timg::TimerGroup, usb_serial_jtag::UsbSerialJtag}; use hil_test as _; #[test] fn creating_peripheral_does_not_break_debug_connection() { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let System { + peripherals, + clocks, + .. + } = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); From 21baf99755742cce34092958d8c698380f50ac9b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Mon, 26 Aug 2024 11:21:26 +0200 Subject: [PATCH 02/19] Turn sw interrupt control into a virtual peripheral --- esp-hal/src/interrupt/mod.rs | 30 ++++++++++--------- esp-hal/src/lib.rs | 4 --- esp-hal/src/soc/esp32/peripherals.rs | 1 + esp-hal/src/soc/esp32c2/peripherals.rs | 1 + esp-hal/src/soc/esp32c3/peripherals.rs | 1 + esp-hal/src/soc/esp32c6/peripherals.rs | 1 + esp-hal/src/soc/esp32h2/peripherals.rs | 1 + esp-hal/src/soc/esp32s2/peripherals.rs | 1 + esp-hal/src/soc/esp32s3/peripherals.rs | 1 + esp-hal/src/system.rs | 8 +++-- .../src/bin/embassy_multicore_interrupt.rs | 8 +++-- examples/src/bin/embassy_multiprio.rs | 6 ++-- examples/src/bin/software_interrupts.rs | 10 +++++-- hil-test/tests/embassy_interrupt_executor.rs | 7 +++-- hil-test/tests/embassy_timers_executors.rs | 5 +++- hil-test/tests/interrupt.rs | 11 +++---- 16 files changed, 57 insertions(+), 39 deletions(-) diff --git a/esp-hal/src/interrupt/mod.rs b/esp-hal/src/interrupt/mod.rs index 8831611fedf..391aee4d08e 100644 --- a/esp-hal/src/interrupt/mod.rs +++ b/esp-hal/src/interrupt/mod.rs @@ -31,27 +31,29 @@ //! ```rust, no_run #![doc = crate::before_snippet!()] //! let system = esp_hal::init(CpuClock::boot_default()); -//! let mut sw_int = system.software_interrupt_control; -//! critical_section::with(|cs| { -//! sw_int -//! .software_interrupt0 -//! .set_interrupt_handler(swint0_handler); -//! SWINT0 -//! .borrow_ref_mut(cs) -//! .replace(sw_int.software_interrupt0); -//! }); //! -//! critical_section::with(|cs| { -//! SWINT0.borrow_ref(cs).as_ref().unwrap().raise(); -//! }); +//! let mut sw_int = +//! SoftwareInterruptControl::new(system.peripherals.SW_INTERRUPT); +//! critical_section::with(|cs| { +//! sw_int +//! .software_interrupt0 +//! .set_interrupt_handler(swint0_handler); +//! SWINT0 +//! .borrow_ref_mut(cs) +//! .replace(sw_int.software_interrupt0); +//! }); //! -//! loop {} +//! critical_section::with(|cs| { +//! SWINT0.borrow_ref(cs).as_ref().unwrap().raise(); +//! }); +//! # +//! # loop {} //! # } //! //! # use core::cell::RefCell; //! # //! # use critical_section::Mutex; -//! # use esp_hal::system::SoftwareInterrupt; +//! # use esp_hal::system::{SoftwareInterrupt, SoftwareInterruptControl}; //! # use esp_hal::interrupt::Priority; //! # use esp_hal::interrupt::InterruptHandler; //! # diff --git a/esp-hal/src/lib.rs b/esp-hal/src/lib.rs index ebf9e3bcdcc..559c11616ab 100644 --- a/esp-hal/src/lib.rs +++ b/esp-hal/src/lib.rs @@ -643,9 +643,6 @@ pub struct System { /// The configured clocks. pub clocks: Clocks<'static>, - - /// The available software interrupts. - pub software_interrupt_control: crate::system::SoftwareInterruptControl, } /// Initialize the system. @@ -655,6 +652,5 @@ pub fn init(clock_config: CpuClock) -> System { System { peripherals, clocks: ClockControl::new(clock_config).freeze(), - software_interrupt_control: crate::system::SoftwareInterruptControl::new(), } } diff --git a/esp-hal/src/soc/esp32/peripherals.rs b/esp-hal/src/soc/esp32/peripherals.rs index fe2be78c2be..ab9b31ce6d1 100644 --- a/esp-hal/src/soc/esp32/peripherals.rs +++ b/esp-hal/src/soc/esp32/peripherals.rs @@ -63,6 +63,7 @@ crate::peripherals! { SPI2 <= SPI2 (SPI2_DMA, SPI2), SPI3 <= SPI3 (SPI3_DMA, SPI3), SYSTEM <= DPORT, + SW_INTERRUPT <= virtual, TIMG0 <= TIMG0, TIMG1 <= TIMG1, TOUCH <= virtual, diff --git a/esp-hal/src/soc/esp32c2/peripherals.rs b/esp-hal/src/soc/esp32c2/peripherals.rs index adf05427afc..3cd86959d96 100644 --- a/esp-hal/src/soc/esp32c2/peripherals.rs +++ b/esp-hal/src/soc/esp32c2/peripherals.rs @@ -43,6 +43,7 @@ crate::peripherals! { SPI2 <= SPI2 (SPI2), SYSTEM <= SYSTEM, SYSTIMER <= SYSTIMER, + SW_INTERRUPT <= virtual, TIMG0 <= TIMG0, UART0 <= UART0, UART1 <= UART1, diff --git a/esp-hal/src/soc/esp32c3/peripherals.rs b/esp-hal/src/soc/esp32c3/peripherals.rs index 4ffd2aa402a..dd5308df0c2 100644 --- a/esp-hal/src/soc/esp32c3/peripherals.rs +++ b/esp-hal/src/soc/esp32c3/peripherals.rs @@ -50,6 +50,7 @@ crate::peripherals! { SPI2 <= SPI2 (SPI2), SYSTEM <= SYSTEM, SYSTIMER <= SYSTIMER, + SW_INTERRUPT <= virtual, TIMG0 <= TIMG0, TIMG1 <= TIMG1, TWAI0 <= TWAI0, diff --git a/esp-hal/src/soc/esp32c6/peripherals.rs b/esp-hal/src/soc/esp32c6/peripherals.rs index 6952cdc0d00..ef74459ed22 100644 --- a/esp-hal/src/soc/esp32c6/peripherals.rs +++ b/esp-hal/src/soc/esp32c6/peripherals.rs @@ -76,6 +76,7 @@ crate::peripherals! { SPI2 <= SPI2 (SPI2), SYSTEM <= PCR, SYSTIMER <= SYSTIMER, + SW_INTERRUPT <= virtual, TEE <= TEE, TIMG0 <= TIMG0, TIMG1 <= TIMG1, diff --git a/esp-hal/src/soc/esp32h2/peripherals.rs b/esp-hal/src/soc/esp32h2/peripherals.rs index 205c1bad47c..7fbda39c981 100644 --- a/esp-hal/src/soc/esp32h2/peripherals.rs +++ b/esp-hal/src/soc/esp32h2/peripherals.rs @@ -68,6 +68,7 @@ crate::peripherals! { SPI2 <= SPI2 (SPI2), SYSTEM <= PCR, SYSTIMER <= SYSTIMER, + SW_INTERRUPT <= virtual, TEE <= TEE, TIMG0 <= TIMG0, TIMG1 <= TIMG1, diff --git a/esp-hal/src/soc/esp32s2/peripherals.rs b/esp-hal/src/soc/esp32s2/peripherals.rs index 7ed7c128248..31d989cf28f 100644 --- a/esp-hal/src/soc/esp32s2/peripherals.rs +++ b/esp-hal/src/soc/esp32s2/peripherals.rs @@ -58,6 +58,7 @@ crate::peripherals! { SYSCON <= SYSCON, SYSTEM <= SYSTEM, SYSTIMER <= SYSTIMER, + SW_INTERRUPT <= virtual, TIMG0 <= TIMG0, TIMG1 <= TIMG1, TWAI0 <= TWAI0, diff --git a/esp-hal/src/soc/esp32s3/peripherals.rs b/esp-hal/src/soc/esp32s3/peripherals.rs index 8671a1e516c..9e0592abf52 100644 --- a/esp-hal/src/soc/esp32s3/peripherals.rs +++ b/esp-hal/src/soc/esp32s3/peripherals.rs @@ -63,6 +63,7 @@ crate::peripherals! { SPI3 <= SPI3 (SPI3), SYSTEM <= SYSTEM, SYSTIMER <= SYSTIMER, + SW_INTERRUPT <= virtual, TIMG0 <= TIMG0, TIMG1 <= TIMG1, TWAI0 <= TWAI0, diff --git a/esp-hal/src/system.rs b/esp-hal/src/system.rs index d807269c5bd..364930a64c2 100755 --- a/esp-hal/src/system.rs +++ b/esp-hal/src/system.rs @@ -21,7 +21,9 @@ #![doc = crate::before_snippet!()] //! let system = esp_hal::init(CpuClock::boot_default()); //! -//! let mut int0 = system.software_interrupt_control.software_interrupt0; +//! let sw_ints = +//! SoftwareInterruptControl::new(system.peripherals.SW_INTERRUPT); +//! let mut int0 = sw_ints.software_interrupt0; //! //! critical_section::with(|cs| { //! int0.set_interrupt_handler(interrupt_handler); @@ -31,7 +33,7 @@ //! //! use core::cell::RefCell; //! use critical_section::Mutex; -//! use esp_hal::system::SoftwareInterrupt; +//! use esp_hal::system::{SoftwareInterrupt, SoftwareInterruptControl}; //! //! static SWINT0: Mutex>>> = //! Mutex::new(RefCell::new(None)); @@ -302,7 +304,7 @@ pub struct SoftwareInterruptControl { } impl SoftwareInterruptControl { - pub(crate) fn new() -> Self { + pub fn new(_peripheral: crate::peripherals::SW_INTERRUPT) -> Self { SoftwareInterruptControl { software_interrupt0: SoftwareInterrupt {}, software_interrupt1: SoftwareInterrupt {}, diff --git a/examples/src/bin/embassy_multicore_interrupt.rs b/examples/src/bin/embassy_multicore_interrupt.rs index 4bff7915b82..ed469647765 100644 --- a/examples/src/bin/embassy_multicore_interrupt.rs +++ b/examples/src/bin/embassy_multicore_interrupt.rs @@ -22,6 +22,7 @@ use esp_hal::{ get_core, gpio::{AnyOutput, Io, Level}, interrupt::Priority, + system::SoftwareInterruptControl, prelude::*, timer::{timg::TimerGroup, ErasedTimer}, }; @@ -74,9 +75,10 @@ fn main() -> ! { let System { peripherals, clocks, - .. } = esp_hal::init(CpuClock::boot_default()); + let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); + let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); @@ -93,7 +95,7 @@ fn main() -> ! { static EXECUTOR_CORE_1: StaticCell> = StaticCell::new(); let executor_core1 = - InterruptExecutor::new(system.software_interrupt_control.software_interrupt1); + InterruptExecutor::new(sw_ints.software_interrupt1); let executor_core1 = EXECUTOR_CORE_1.init(executor_core1); let _guard = cpu_control @@ -109,7 +111,7 @@ fn main() -> ! { static EXECUTOR_CORE_0: StaticCell> = StaticCell::new(); let executor_core0 = - InterruptExecutor::new(system.software_interrupt_control.software_interrupt0); + InterruptExecutor::new(sw_ints.software_interrupt0); let executor_core0 = EXECUTOR_CORE_0.init(executor_core0); let spawner = executor_core0.start(Priority::Priority1); diff --git a/examples/src/bin/embassy_multiprio.rs b/examples/src/bin/embassy_multiprio.rs index bdb0672ddda..c28349daea9 100644 --- a/examples/src/bin/embassy_multiprio.rs +++ b/examples/src/bin/embassy_multiprio.rs @@ -25,6 +25,7 @@ use embassy_time::{Duration, Instant, Ticker, Timer}; use esp_backtrace as _; use esp_hal::{ interrupt::Priority, + system::SoftwareInterruptControl, timer::{timg::TimerGroup, ErasedTimer}, }; use esp_hal_embassy::InterruptExecutor; @@ -74,9 +75,10 @@ async fn main(low_prio_spawner: Spawner) { let System { peripherals, clocks, - .. } = esp_hal::init(CpuClock::boot_default()); + let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); + let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); let timer0: ErasedTimer = timg0.timer0.into(); @@ -94,7 +96,7 @@ async fn main(low_prio_spawner: Spawner) { esp_hal_embassy::init(&clocks, [timer0, timer1]); static EXECUTOR: StaticCell> = StaticCell::new(); - let executor = InterruptExecutor::new(system.software_interrupt_control.software_interrupt2); + let executor = InterruptExecutor::new(sw_ints.software_interrupt2); let executor = EXECUTOR.init(executor); let spawner = executor.start(Priority::Priority3); diff --git a/examples/src/bin/software_interrupts.rs b/examples/src/bin/software_interrupts.rs index b15e233cde4..8cae314f47c 100644 --- a/examples/src/bin/software_interrupts.rs +++ b/examples/src/bin/software_interrupts.rs @@ -13,7 +13,11 @@ use core::cell::RefCell; use critical_section::Mutex; use esp_backtrace as _; -use esp_hal::{delay::Delay, prelude::*, system::SoftwareInterrupt}; +use esp_hal::{ + delay::Delay, + prelude::*, + system::{SoftwareInterrupt, SoftwareInterruptControl}, +}; static SWINT0: Mutex>>> = Mutex::new(RefCell::new(None)); static SWINT1: Mutex>>> = Mutex::new(RefCell::new(None)); @@ -24,10 +28,12 @@ static SWINT3: Mutex>>> = Mutex::new(RefCell fn main() -> ! { let System { clocks, - software_interrupt_control: mut sw_int, + peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let mut sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); + critical_section::with(|cs| { sw_int .software_interrupt0 diff --git a/hil-test/tests/embassy_interrupt_executor.rs b/hil-test/tests/embassy_interrupt_executor.rs index 6080b8b9edc..da440e10587 100644 --- a/hil-test/tests/embassy_interrupt_executor.rs +++ b/hil-test/tests/embassy_interrupt_executor.rs @@ -12,7 +12,7 @@ use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, signal::Signal} use esp_hal::{ clock::CpuClock, interrupt::Priority, - system::SoftwareInterrupt, + system::{SoftwareInterrupt, SoftwareInterruptControl}, timer::timg::TimerGroup, }; use esp_hal_embassy::InterruptExecutor; @@ -43,12 +43,13 @@ mod test { #[init] fn init() -> SoftwareInterrupt<1> { - let system = esp_hal::init(CpuClock::boot_default()); + let System{peripherals,..} = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); - system.software_interrupt_control.software_interrupt1 + let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); + sw_ints.software_interrupt1 } #[test] diff --git a/hil-test/tests/embassy_timers_executors.rs b/hil-test/tests/embassy_timers_executors.rs index ab1196c677c..61026762374 100644 --- a/hil-test/tests/embassy_timers_executors.rs +++ b/hil-test/tests/embassy_timers_executors.rs @@ -15,6 +15,7 @@ use esp_hal::{ }; use esp_hal::{ prelude::*, + system::SoftwareInterruptControl, timer::{timg::TimerGroup, ErasedTimer, OneShotTimer, PeriodicTimer}, }; #[cfg(not(feature = "esp32"))] @@ -220,9 +221,11 @@ mod test { let timers = mk_static!([OneShotTimer; 2], [timer0, timer1]); esp_hal_embassy::init(&system.clocks, timers); + let sw_ints = SoftwareInterruptControl::new(system.peripherals.SW_INTERRUPT); + let executor = mk_static!( InterruptExecutor<2>, - InterruptExecutor::new(system.software_interrupt_control.software_interrupt2) + InterruptExecutor::new(sw_ints.software_interrupt2) ); #[embassy_executor::task] diff --git a/hil-test/tests/interrupt.rs b/hil-test/tests/interrupt.rs index 37fc5eb0e2a..b8b76f5e03d 100644 --- a/hil-test/tests/interrupt.rs +++ b/hil-test/tests/interrupt.rs @@ -14,7 +14,7 @@ use esp_hal::{ interrupt::{self, *}, peripherals::Interrupt, prelude::*, - system::SoftwareInterrupt, + system::{SoftwareInterrupt, SoftwareInterruptControl}, }; use hil_test as _; @@ -27,11 +27,8 @@ struct Context { impl Context { pub fn init() -> Self { - let System { - peripherals, - software_interrupt_control: sw_int, - .. - } = esp_hal::init(CpuClock::max()); + let System { peripherals, .. } = esp_hal::init(CpuClock::max()); + let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); cfg_if::cfg_if! { if #[cfg(any(feature = "esp32c6", feature = "esp32h2"))] { @@ -46,7 +43,7 @@ impl Context { critical_section::with(|cs| { SWINT0 .borrow_ref_mut(cs) - .replace(sw_int.software_interrupt0) + .replace(sw_ints.software_interrupt0) }); interrupt::enable_direct( Interrupt::FROM_CPU_INTR0, From a597ff8deed07aa68b37bb687033172c935038de Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Mon, 26 Aug 2024 11:21:58 +0200 Subject: [PATCH 03/19] Return a tuple instead of a named struct --- esp-hal/src/aes/mod.rs | 4 +- esp-hal/src/analog/adc/mod.rs | 6 +- esp-hal/src/clock/mod.rs | 2 +- esp-hal/src/delay.rs | 4 +- esp-hal/src/dma/mod.rs | 9 +-- esp-hal/src/gpio/mod.rs | 3 +- esp-hal/src/gpio/rtc_io.rs | 3 +- esp-hal/src/i2c.rs | 6 +- esp-hal/src/i2s.rs | 9 +-- esp-hal/src/interrupt/mod.rs | 4 +- esp-hal/src/lcd_cam/cam.rs | 9 +-- esp-hal/src/lcd_cam/lcd/i8080.rs | 10 +-- esp-hal/src/ledc/mod.rs | 6 +- esp-hal/src/lib.rs | 24 ++---- esp-hal/src/mcpwm/mod.rs | 10 +-- esp-hal/src/mcpwm/operator.rs | 10 +-- esp-hal/src/prelude.rs | 2 +- esp-hal/src/rmt.rs | 6 +- esp-hal/src/rom/md5.rs | 12 +-- esp-hal/src/rtc_cntl/mod.rs | 6 +- esp-hal/src/soc/esp32/efuse/mod.rs | 6 +- esp-hal/src/soc/esp32c2/efuse/mod.rs | 6 +- esp-hal/src/soc/esp32c3/efuse/mod.rs | 6 +- esp-hal/src/soc/esp32c6/efuse/mod.rs | 6 +- esp-hal/src/soc/esp32h2/efuse/mod.rs | 6 +- esp-hal/src/soc/esp32s2/efuse/mod.rs | 6 +- esp-hal/src/soc/esp32s2/ulp_core.rs | 3 +- esp-hal/src/soc/esp32s3/cpu_control.rs | 6 +- esp-hal/src/soc/esp32s3/efuse/mod.rs | 6 +- esp-hal/src/soc/esp32s3/ulp_core.rs | 4 +- esp-hal/src/spi/master.rs | 8 +- esp-hal/src/spi/slave.rs | 7 +- esp-hal/src/system.rs | 4 +- esp-hal/src/timer/mod.rs | 6 +- esp-hal/src/timer/systimer.rs | 6 +- esp-hal/src/timer/timg.rs | 6 +- esp-hal/src/twai/mod.rs | 16 ++-- esp-hal/src/uart.rs | 35 +++++---- esp-hal/src/usb_serial_jtag.rs | 8 +- examples/src/bin/adc.rs | 6 +- examples/src/bin/adc_cal.rs | 6 +- examples/src/bin/advanced_serial.rs | 6 +- examples/src/bin/blinky.rs | 6 +- examples/src/bin/blinky_erased_pins.rs | 6 +- examples/src/bin/dac.rs | 6 +- examples/src/bin/debug_assist.rs | 6 +- examples/src/bin/dma_extmem2mem.rs | 6 +- examples/src/bin/dma_mem2mem.rs | 6 +- examples/src/bin/embassy_hello_world.rs | 6 +- examples/src/bin/embassy_i2c.rs | 6 +- .../embassy_i2c_bmp180_calibration_data.rs | 6 +- examples/src/bin/embassy_i2s_read.rs | 6 +- examples/src/bin/embassy_i2s_sound.rs | 6 +- examples/src/bin/embassy_multicore.rs | 6 +- .../src/bin/embassy_multicore_interrupt.rs | 13 +--- examples/src/bin/embassy_multiprio.rs | 5 +- examples/src/bin/embassy_parl_io_rx.rs | 6 +- examples/src/bin/embassy_parl_io_tx.rs | 6 +- examples/src/bin/embassy_rmt_rx.rs | 6 +- examples/src/bin/embassy_rmt_tx.rs | 7 +- examples/src/bin/embassy_serial.rs | 6 +- examples/src/bin/embassy_spi.rs | 6 +- examples/src/bin/embassy_touch.rs | 7 +- examples/src/bin/embassy_twai.rs | 6 +- examples/src/bin/embassy_usb_serial.rs | 6 +- examples/src/bin/embassy_usb_serial_jtag.rs | 6 +- examples/src/bin/embassy_wait.rs | 6 +- examples/src/bin/etm_blinky_systimer.rs | 2 +- examples/src/bin/etm_gpio.rs | 2 +- examples/src/bin/etm_timer.rs | 6 +- examples/src/bin/gpio_interrupt.rs | 6 +- examples/src/bin/hello_rgb.rs | 6 +- examples/src/bin/hello_world.rs | 6 +- examples/src/bin/hmac.rs | 2 +- .../src/bin/i2c_bmp180_calibration_data.rs | 6 +- examples/src/bin/i2c_display.rs | 6 +- examples/src/bin/i2s_read.rs | 6 +- examples/src/bin/i2s_sound.rs | 6 +- .../src/bin/ieee802154_receive_all_frames.rs | 2 +- examples/src/bin/ieee802154_receive_frame.rs | 4 +- .../bin/ieee802154_send_broadcast_frame.rs | 6 +- examples/src/bin/ieee802154_send_frame.rs | 6 +- examples/src/bin/ieee802154_sniffer.rs | 6 +- examples/src/bin/lcd_cam_ov2640.rs | 6 +- examples/src/bin/lcd_i8080.rs | 6 +- examples/src/bin/ledc.rs | 6 +- examples/src/bin/lp_core_basic.rs | 2 +- examples/src/bin/lp_core_i2c.rs | 2 +- examples/src/bin/lp_core_uart.rs | 6 +- examples/src/bin/mcpwm.rs | 6 +- examples/src/bin/multicore.rs | 6 +- examples/src/bin/parl_io_rx.rs | 6 +- examples/src/bin/parl_io_tx.rs | 6 +- examples/src/bin/pcnt_encoder.rs | 2 +- examples/src/bin/psram_octal.rs | 2 +- examples/src/bin/psram_quad.rs | 2 +- examples/src/bin/qspi_flash.rs | 6 +- examples/src/bin/ram.rs | 6 +- examples/src/bin/rmt_rx.rs | 6 +- examples/src/bin/rmt_tx.rs | 6 +- examples/src/bin/rng.rs | 2 +- examples/src/bin/rtc_time.rs | 6 +- examples/src/bin/rtc_watchdog.rs | 2 +- examples/src/bin/serial_interrupts.rs | 6 +- examples/src/bin/sleep_timer.rs | 6 +- examples/src/bin/sleep_timer_ext0.rs | 6 +- examples/src/bin/sleep_timer_ext1.rs | 6 +- examples/src/bin/sleep_timer_lpio.rs | 6 +- examples/src/bin/sleep_timer_rtcio.rs | 6 +- examples/src/bin/software_interrupts.rs | 6 +- .../spi_halfduplex_read_manufacturer_id.rs | 6 +- examples/src/bin/spi_loopback.rs | 6 +- examples/src/bin/spi_loopback_dma.rs | 6 +- examples/src/bin/spi_slave_dma.rs | 6 +- examples/src/bin/systimer.rs | 6 +- examples/src/bin/timer_interrupt.rs | 6 +- examples/src/bin/touch.rs | 6 +- examples/src/bin/twai.rs | 6 +- examples/src/bin/ulp_riscv_core_basic.rs | 2 +- examples/src/bin/usb_serial.rs | 2 +- examples/src/bin/usb_serial_jtag.rs | 6 +- examples/src/bin/watchdog.rs | 6 +- examples/src/bin/wifi_80211_tx.rs | 7 +- examples/src/bin/wifi_access_point.rs | 7 +- .../src/bin/wifi_access_point_with_sta.rs | 7 +- examples/src/bin/wifi_bench.rs | 7 +- examples/src/bin/wifi_ble.rs | 7 +- examples/src/bin/wifi_coex.rs | 7 +- examples/src/bin/wifi_dhcp.rs | 7 +- examples/src/bin/wifi_embassy_access_point.rs | 7 +- .../bin/wifi_embassy_access_point_with_sta.rs | 7 +- examples/src/bin/wifi_embassy_bench.rs | 7 +- examples/src/bin/wifi_embassy_ble.rs | 7 +- examples/src/bin/wifi_embassy_dhcp.rs | 7 +- examples/src/bin/wifi_embassy_esp_now.rs | 7 +- .../src/bin/wifi_embassy_esp_now_duplex.rs | 7 +- examples/src/bin/wifi_esp_now.rs | 7 +- examples/src/bin/wifi_sniffer.rs | 7 +- examples/src/bin/wifi_static_ip.rs | 7 +- hil-test/tests/aes.rs | 2 +- hil-test/tests/aes_dma.rs | 4 +- hil-test/tests/clock_monitor.rs | 4 +- hil-test/tests/delay.rs | 4 +- hil-test/tests/dma_mem2mem.rs | 8 +- hil-test/tests/ecc.rs | 2 +- hil-test/tests/embassy_interrupt_executor.rs | 2 +- hil-test/tests/embassy_timers_executors.rs | 76 ++++++++++--------- hil-test/tests/get_time.rs | 2 +- hil-test/tests/gpio.rs | 10 +-- hil-test/tests/i2s.rs | 6 +- hil-test/tests/i2s_async.rs | 6 +- hil-test/tests/interrupt.rs | 58 +++++++------- hil-test/tests/lcd_cam_i8080.rs | 6 +- hil-test/tests/lcd_cam_i8080_async.rs | 6 +- hil-test/tests/pcnt.rs | 6 +- hil-test/tests/rmt.rs | 6 +- hil-test/tests/rsa.rs | 2 +- hil-test/tests/sha.rs | 4 +- hil-test/tests/spi_full_duplex.rs | 6 +- hil-test/tests/spi_full_duplex_dma.rs | 8 +- hil-test/tests/spi_full_duplex_dma_async.rs | 8 +- hil-test/tests/spi_half_duplex_read.rs | 6 +- hil-test/tests/spi_half_duplex_write.rs | 6 +- hil-test/tests/systimer.rs | 6 +- hil-test/tests/twai.rs | 6 +- hil-test/tests/uart.rs | 6 +- hil-test/tests/uart_async.rs | 6 +- hil-test/tests/uart_tx_rx.rs | 6 +- hil-test/tests/uart_tx_rx_async.rs | 6 +- hil-test/tests/usb_serial_jtag.rs | 6 +- 170 files changed, 338 insertions(+), 819 deletions(-) diff --git a/esp-hal/src/aes/mod.rs b/esp-hal/src/aes/mod.rs index cfacc307bc1..f6f01bfef65 100644 --- a/esp-hal/src/aes/mod.rs +++ b/esp-hal/src/aes/mod.rs @@ -29,12 +29,10 @@ //! # let mut keybuf = [0_u8; 16]; //! # keybuf[..keytext.len()].copy_from_slice(keytext); //! # -//! let system = esp_hal::init(CpuClock::boot_default()); -//! //! let mut block = [0_u8; 16]; //! block[..plaintext.len()].copy_from_slice(plaintext); //! -//! let mut aes = Aes::new(system.peripherals.AES); +//! let mut aes = Aes::new(peripherals.AES); //! aes.process(&mut block, Mode::Encryption128, keybuf); //! //! // The encryption happens in-place, so the ciphertext is in `block` diff --git a/esp-hal/src/analog/adc/mod.rs b/esp-hal/src/analog/adc/mod.rs index b15e1cfa83d..7a1aa62413f 100644 --- a/esp-hal/src/analog/adc/mod.rs +++ b/esp-hal/src/analog/adc/mod.rs @@ -32,7 +32,7 @@ //! # use esp_hal::analog::adc::Adc; //! # use esp_hal::delay::Delay; //! # use esp_hal::gpio::Io; -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); #![cfg_attr(esp32, doc = "let analog_pin = io.pins.gpio32;")] #![cfg_attr(any(esp32s2, esp32s3), doc = "let analog_pin = io.pins.gpio3;")] #![cfg_attr( @@ -44,9 +44,9 @@ //! analog_pin, //! Attenuation::Attenuation11dB, //! ); -//! let mut adc1 = Adc::new(system.peripherals.ADC1, adc1_config); +//! let mut adc1 = Adc::new(peripherals.ADC1, adc1_config); //! -//! let mut delay = Delay::new(&system.clocks); +//! let mut delay = Delay::new(&clocks); //! //! loop { //! let pin_value: u16 = nb::block!(adc1.read_oneshot(&mut pin)).unwrap(); diff --git a/esp-hal/src/clock/mod.rs b/esp-hal/src/clock/mod.rs index 2ac5d237ae9..81ea9c2b0e3 100644 --- a/esp-hal/src/clock/mod.rs +++ b/esp-hal/src/clock/mod.rs @@ -59,7 +59,7 @@ #![cfg_attr(esp32h2, doc = "// let system = esp_hal::init(CpuClock::Clock96MHz);")] //! // //! // Initialize with default clock frequency for this chip -//! // let system = esp_hal::init(CpuClock::boot_default()); +//! // let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); //! # } //! ``` diff --git a/esp-hal/src/delay.rs b/esp-hal/src/delay.rs index a43aedb6629..2b55786c455 100644 --- a/esp-hal/src/delay.rs +++ b/esp-hal/src/delay.rs @@ -22,9 +22,7 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::delay::Delay; //! # use embedded_hal::delay::DelayNs; -//! let system = esp_hal::init(CpuClock::boot_default()); -//! -//! let mut delay = Delay::new(&system.clocks); +//! let mut delay = Delay::new(&clocks); //! //! delay.delay_ms(1000 as u32); //! # } diff --git a/esp-hal/src/dma/mod.rs b/esp-hal/src/dma/mod.rs index 22b14f7cf3c..059bd98b1a1 100644 --- a/esp-hal/src/dma/mod.rs +++ b/esp-hal/src/dma/mod.rs @@ -21,21 +21,20 @@ //! # use esp_hal::gpio::Io; //! # use esp_hal::spi::{master::Spi, SpiMode}; //! # use esp_hal::dma::{Dma, DmaPriority}; -//! let system = esp_hal::init(CpuClock::boot_default()); -//! let dma = Dma::new(system.peripherals.DMA); +//! let dma = Dma::new(peripherals.DMA); #![cfg_attr(any(esp32, esp32s2), doc = "let dma_channel = dma.spi2channel;")] #![cfg_attr(not(any(esp32, esp32s2)), doc = "let dma_channel = dma.channel0;")] -//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! let sclk = io.pins.gpio0; //! let miso = io.pins.gpio2; //! let mosi = io.pins.gpio4; //! let cs = io.pins.gpio5; //! //! let mut spi = Spi::new( -//! system.peripherals.SPI2, +//! peripherals.SPI2, //! 100.kHz(), //! SpiMode::Mode0, -//! &system.clocks +//! &clocks //! ) //! .with_pins(Some(sclk), Some(mosi), Some(miso), Some(cs)) //! .with_dma(dma_channel.configure( diff --git a/esp-hal/src/gpio/mod.rs b/esp-hal/src/gpio/mod.rs index 4f29cd20769..d89deb7ca45 100644 --- a/esp-hal/src/gpio/mod.rs +++ b/esp-hal/src/gpio/mod.rs @@ -37,8 +37,7 @@ //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::gpio::{Io, Level, Output}; -//! let system = esp_hal::init(CpuClock::boot_default()); -//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! let mut led = Output::new(io.pins.gpio5, Level::High); //! # } //! ``` diff --git a/esp-hal/src/gpio/rtc_io.rs b/esp-hal/src/gpio/rtc_io.rs index 5e77e7b7191..db3ed328829 100644 --- a/esp-hal/src/gpio/rtc_io.rs +++ b/esp-hal/src/gpio/rtc_io.rs @@ -24,8 +24,7 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::gpio::rtc_io::LowPowerOutput; //! # use esp_hal::gpio::Io; -//! let system = esp_hal::init(CpuClock::boot_default()); -//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! // configure GPIO 1 as ULP output pin //! let lp_pin = LowPowerOutput::<'static, 1>::new(io.pins.gpio1); //! # } diff --git a/esp-hal/src/i2c.rs b/esp-hal/src/i2c.rs index 2a54c84c314..d2c2ca0c6b0 100644 --- a/esp-hal/src/i2c.rs +++ b/esp-hal/src/i2c.rs @@ -33,16 +33,16 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::i2c::I2C; //! # use esp_hal::gpio::Io; -//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! //! // Create a new peripheral object with the described wiring //! // and standard I2C clock speed. //! let mut i2c = I2C::new( -//! system.peripherals.I2C0, +//! peripherals.I2C0, //! io.pins.gpio1, //! io.pins.gpio2, //! 100.kHz(), -//! &system.clocks, +//! &clocks, //! ); //! //! loop { diff --git a/esp-hal/src/i2s.rs b/esp-hal/src/i2s.rs index 79717993c1b..ac390c9fde0 100644 --- a/esp-hal/src/i2s.rs +++ b/esp-hal/src/i2s.rs @@ -36,16 +36,15 @@ //! # use esp_hal::gpio::Io; //! # use esp_hal::dma_buffers; //! # use esp_hal::dma::{Dma, DmaPriority}; -//! let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); -//! let dma = Dma::new(system.peripherals.DMA); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! let dma = Dma::new(peripherals.DMA); #![cfg_attr(any(esp32, esp32s2), doc = "let dma_channel = dma.i2s0channel;")] #![cfg_attr(not(any(esp32, esp32s2)), doc = "let dma_channel = dma.channel0;")] //! let (_, tx_descriptors, mut rx_buffer, rx_descriptors) = //! dma_buffers!(0, 4 * 4092); //! //! let i2s = I2s::new( -//! system.peripherals.I2S0, +//! peripherals.I2S0, //! Standard::Philips, //! DataFormat::Data16Channel16, //! 44100.Hz(), @@ -55,7 +54,7 @@ //! ), //! tx_descriptors, //! rx_descriptors, -//! &system.clocks, +//! &clocks, //! ); #![cfg_attr(not(esp32), doc = "let i2s = i2s.with_mclk(io.pins.gpio0);")] //! let mut i2s_rx = i2s.i2s_rx diff --git a/esp-hal/src/interrupt/mod.rs b/esp-hal/src/interrupt/mod.rs index 391aee4d08e..9d60824f080 100644 --- a/esp-hal/src/interrupt/mod.rs +++ b/esp-hal/src/interrupt/mod.rs @@ -30,10 +30,8 @@ //! //! ```rust, no_run #![doc = crate::before_snippet!()] -//! let system = esp_hal::init(CpuClock::boot_default()); -//! //! let mut sw_int = -//! SoftwareInterruptControl::new(system.peripherals.SW_INTERRUPT); +//! SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); //! critical_section::with(|cs| { //! sw_int //! .software_interrupt0 diff --git a/esp-hal/src/lcd_cam/cam.rs b/esp-hal/src/lcd_cam/cam.rs index b45523c16b7..a37a6f40fe3 100644 --- a/esp-hal/src/lcd_cam/cam.rs +++ b/esp-hal/src/lcd_cam/cam.rs @@ -21,10 +21,9 @@ //! # use fugit::RateExtU32; //! # use esp_hal::dma_buffers; //! # use esp_hal::dma::{Dma, DmaPriority}; -//! let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! -//! # let dma = Dma::new(system.peripherals.DMA); +//! # let dma = Dma::new(peripherals.DMA); //! # let channel = dma.channel0; //! //! # let (tx_buffer, tx_descriptors, _, rx_descriptors) = dma_buffers!(32678, 0); @@ -49,14 +48,14 @@ //! io.pins.gpio16, //! ); //! -//! let lcd_cam = LcdCam::new(system.peripherals.LCD_CAM); +//! let lcd_cam = LcdCam::new(peripherals.LCD_CAM); //! let mut camera = Camera::new( //! lcd_cam.cam, //! channel.rx, //! rx_descriptors, //! data_pins, //! 20u32.MHz(), -//! &system.clocks +//! &clocks //! ) //! // Remove this for slave mode. //! .with_master_clock(mclk_pin) diff --git a/esp-hal/src/lcd_cam/lcd/i8080.rs b/esp-hal/src/lcd_cam/lcd/i8080.rs index a5b6272ddb4..27af36a8578 100644 --- a/esp-hal/src/lcd_cam/lcd/i8080.rs +++ b/esp-hal/src/lcd_cam/lcd/i8080.rs @@ -19,11 +19,9 @@ //! # use esp_hal::lcd_cam::{LcdCam, lcd::i8080::{Config, I8080, TxEightBits}}; //! # use esp_hal::dma_buffers; //! # use esp_hal::dma::{Dma, DmaPriority}; -//! # -//! let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! -//! # let dma = Dma::new(system.peripherals.DMA); +//! # let dma = Dma::new(peripherals.DMA); //! # let channel = dma.channel0; //! //! # let (tx_buffer, tx_descriptors, _, rx_descriptors) = dma_buffers!(32678, 0); @@ -43,7 +41,7 @@ //! io.pins.gpio16, //! io.pins.gpio15, //! ); -//! let lcd_cam = LcdCam::new(system.peripherals.LCD_CAM); +//! let lcd_cam = LcdCam::new(peripherals.LCD_CAM); //! //! let mut i8080 = I8080::new( //! lcd_cam.lcd, @@ -52,7 +50,7 @@ //! tx_pins, //! 20.MHz(), //! Config::default(), -//! &system.clocks, +//! &clocks, //! ) //! .with_ctrl_pins(io.pins.gpio0, io.pins.gpio47); //! diff --git a/esp-hal/src/ledc/mod.rs b/esp-hal/src/ledc/mod.rs index 31fe16fe549..86a8f18a5fb 100644 --- a/esp-hal/src/ledc/mod.rs +++ b/esp-hal/src/ledc/mod.rs @@ -30,12 +30,10 @@ //! # use esp_hal::ledc::LowSpeed; //! # use esp_hal::ledc::channel; //! # use esp_hal::gpio::Io; -//! -//! let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let led = io.pins.gpio0; //! -//! let mut ledc = Ledc::new(system.peripherals.LEDC, &system.clocks); +//! let mut ledc = Ledc::new(peripherals.LEDC, &clocks); //! ledc.set_global_slow_clock(LSGlobalClkSource::APBClk); //! //! let mut lstimer0 = ledc.get_timer::(timer::Number::Timer0); diff --git a/esp-hal/src/lib.rs b/esp-hal/src/lib.rs index 559c11616ab..aff3813dc7b 100644 --- a/esp-hal/src/lib.rs +++ b/esp-hal/src/lib.rs @@ -74,13 +74,13 @@ //! //! #[entry] //! fn main() -> ! { -//! let system = esp_hal::init(CpuClock::boot_default()); +//! let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); //! //! // Set GPIO0 as an output, and set its state high initially. -//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! let mut led = Output::new(io.pins.gpio0, Level::High); //! -//! let delay = Delay::new(&system.clocks); +//! let delay = Delay::new(&clocks); //! //! loop { //! led.toggle(); @@ -627,6 +627,7 @@ macro_rules! before_snippet { # loop {} # } # fn main() { +# let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); "# }; } @@ -636,21 +637,10 @@ use crate::{ peripherals::Peripherals, }; -/// System components. -pub struct System { - /// The available peripheral instances. - pub peripherals: Peripherals, - - /// The configured clocks. - pub clocks: Clocks<'static>, -} - /// Initialize the system. -pub fn init(clock_config: CpuClock) -> System { +pub fn init(clock_config: CpuClock) -> (Peripherals, Clocks<'static>) { let peripherals = Peripherals::take(); + let clocks = ClockControl::new(clock_config).freeze(); - System { - peripherals, - clocks: ClockControl::new(clock_config).freeze(), - } + (peripherals, clocks) } diff --git a/esp-hal/src/mcpwm/mod.rs b/esp-hal/src/mcpwm/mod.rs index 9803dce07be..52d8f17821d 100644 --- a/esp-hal/src/mcpwm/mod.rs +++ b/esp-hal/src/mcpwm/mod.rs @@ -54,20 +54,20 @@ //! # use esp_hal::mcpwm::{operator::{DeadTimeCfg, PWMStream, PwmPinConfig}, timer::PwmWorkingMode, McPwm, PeripheralClockConfig}; //! # use esp_hal::gpio::Io; //! -//! # let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let pin = io.pins.gpio0; //! //! // initialize peripheral #![cfg_attr( esp32h2, - doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&system.clocks, 40.MHz()).unwrap();" + doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&clocks, 40.MHz()).unwrap();" )] #![cfg_attr( not(esp32h2), - doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&system.clocks, 32.MHz()).unwrap();" + doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&clocks, 32.MHz()).unwrap();" )] -//! let mut mcpwm = McPwm::new(system.peripherals.MCPWM0, clock_cfg); +//! let mut mcpwm = McPwm::new(peripherals.MCPWM0, clock_cfg); //! //! // connect operator0 to timer0 //! mcpwm.operator0.set_timer(&mcpwm.timer0); diff --git a/esp-hal/src/mcpwm/operator.rs b/esp-hal/src/mcpwm/operator.rs index 3e7ee48fb37..be980e7910d 100644 --- a/esp-hal/src/mcpwm/operator.rs +++ b/esp-hal/src/mcpwm/operator.rs @@ -486,8 +486,8 @@ impl<'d, Pin: OutputPin, PWM: PwmPeripheral, const OP: u8, const IS_A: bool> /// # use esp_hal::mcpwm::{McPwm, PeripheralClockConfig}; /// # use esp_hal::mcpwm::operator::{DeadTimeCfg, PwmPinConfig, PWMStream}; /// # use esp_hal::gpio::Io; -/// let system = esp_hal::init(CpuClock::boot_default()); -/// # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +/// let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +/// # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); /// // active high complementary using PWMA input /// let bridge_active = DeadTimeCfg::new_ahc(); /// // use PWMB as input for both outputs @@ -495,13 +495,13 @@ impl<'d, Pin: OutputPin, PWM: PwmPeripheral, const OP: u8, const IS_A: bool> /// true); #[cfg_attr( esp32h2, - doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&system.clocks, 40.MHz()).unwrap();" + doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&clocks, 40.MHz()).unwrap();" )] #[cfg_attr( not(esp32h2), - doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&system.clocks, 32.MHz()).unwrap();" + doc = "let clock_cfg = PeripheralClockConfig::with_frequency(&clocks, 32.MHz()).unwrap();" )] -/// let mut mcpwm = McPwm::new(system.peripherals.MCPWM0, clock_cfg); +/// let mut mcpwm = McPwm::new(peripherals.MCPWM0, clock_cfg); /// /// let mut pins = mcpwm.operator0.with_linked_pins( /// io.pins.gpio0, diff --git a/esp-hal/src/prelude.rs b/esp-hal/src/prelude.rs index 41a19827407..11ad6b9ae56 100644 --- a/esp-hal/src/prelude.rs +++ b/esp-hal/src/prelude.rs @@ -38,4 +38,4 @@ pub use crate::timer::timg::{ pub use crate::timer::Timer as _esp_hal_timer_Timer; #[cfg(any(uart0, uart1, uart2))] pub use crate::uart::Instance as _esp_hal_uart_Instance; -pub use crate::{clock::CpuClock, entry, macros::*, InterruptConfigurable, System}; +pub use crate::{clock::CpuClock, entry, macros::*, InterruptConfigurable}; diff --git a/esp-hal/src/rmt.rs b/esp-hal/src/rmt.rs index f4a981d84ee..a2efc8eb87a 100644 --- a/esp-hal/src/rmt.rs +++ b/esp-hal/src/rmt.rs @@ -57,12 +57,10 @@ //! # use esp_hal::gpio::Io; //! # use esp_hal::clock::ClockControl; //! # use crate::esp_hal::rmt::TxChannelCreator; -//! # use crate::esp_hal::prelude::_fugit_RateExtU32; -//! let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); #![cfg_attr(esp32h2, doc = "let freq = 32.MHz();")] #![cfg_attr(not(esp32h2), doc = "let freq = 80.MHz();")] -//! let rmt = Rmt::new(system.peripherals.RMT, freq, &system.clocks).unwrap(); +//! let rmt = Rmt::new(peripherals.RMT, freq, &clocks).unwrap(); //! let mut channel = rmt //! .channel0 //! .configure( diff --git a/esp-hal/src/rom/md5.rs b/esp-hal/src/rom/md5.rs index 4759219b49b..85d53017d09 100644 --- a/esp-hal/src/rom/md5.rs +++ b/esp-hal/src/rom/md5.rs @@ -35,9 +35,9 @@ //! # use esp_hal::gpio::Io; //! # use core::writeln; //! # use core::fmt::Write; -//! # let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); -//! # let mut uart0 = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio1, io.pins.gpio2).unwrap(); +//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # let mut uart0 = Uart::new(peripherals.UART0, &clocks, io.pins.gpio1, io.pins.gpio2).unwrap(); //! # let data = "Dummy"; //! let d: md5::Digest = md5::compute(&data); //! writeln!(uart0, "{}", d); @@ -52,9 +52,9 @@ //! # use esp_hal::gpio::Io; //! # use core::writeln; //! # use core::fmt::Write; -//! # let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); -//! # let mut uart0 = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio1, io.pins.gpio2).unwrap(); +//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # let mut uart0 = Uart::new(peripherals.UART0, &clocks, io.pins.gpio1, io.pins.gpio2).unwrap(); //! # let data0 = "Dummy"; //! # let data1 = "Dummy"; //! # diff --git a/esp-hal/src/rtc_cntl/mod.rs b/esp-hal/src/rtc_cntl/mod.rs index 492a6de0c9f..c379228c923 100644 --- a/esp-hal/src/rtc_cntl/mod.rs +++ b/esp-hal/src/rtc_cntl/mod.rs @@ -29,11 +29,9 @@ //! # use crate::esp_hal::prelude::_fugit_ExtU64; //! # use crate::esp_hal::InterruptConfigurable; //! static RWDT: Mutex>> = Mutex::new(RefCell::new(None)); +//! let mut delay = Delay::new(&clocks); //! -//! let system = esp_hal::init(CpuClock::boot_default()); -//! let mut delay = Delay::new(&system.clocks); -//! -//! let mut rtc = Rtc::new(system.peripherals.LPWR); +//! let mut rtc = Rtc::new(peripherals.LPWR); //! //! rtc.set_interrupt_handler(interrupt_handler); //! rtc.rwdt.set_timeout(2000.millis()); diff --git a/esp-hal/src/soc/esp32/efuse/mod.rs b/esp-hal/src/soc/esp32/efuse/mod.rs index 4e275bd4298..a1cee01c9d8 100644 --- a/esp-hal/src/soc/esp32/efuse/mod.rs +++ b/esp-hal/src/soc/esp32/efuse/mod.rs @@ -28,9 +28,9 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); -//! # let mut serial_tx = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); +//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32c2/efuse/mod.rs b/esp-hal/src/soc/esp32c2/efuse/mod.rs index 1e1981cba3d..1da300d4bab 100644 --- a/esp-hal/src/soc/esp32c2/efuse/mod.rs +++ b/esp-hal/src/soc/esp32c2/efuse/mod.rs @@ -25,9 +25,9 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); -//! # let mut serial_tx = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); +//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32c3/efuse/mod.rs b/esp-hal/src/soc/esp32c3/efuse/mod.rs index a897fad9444..fe370f833ac 100644 --- a/esp-hal/src/soc/esp32c3/efuse/mod.rs +++ b/esp-hal/src/soc/esp32c3/efuse/mod.rs @@ -26,9 +26,9 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); -//! # let mut serial_tx = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); +//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32c6/efuse/mod.rs b/esp-hal/src/soc/esp32c6/efuse/mod.rs index 73f8fecc5fd..7441feecbe3 100644 --- a/esp-hal/src/soc/esp32c6/efuse/mod.rs +++ b/esp-hal/src/soc/esp32c6/efuse/mod.rs @@ -26,9 +26,9 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); -//! # let mut serial_tx = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); +//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32h2/efuse/mod.rs b/esp-hal/src/soc/esp32h2/efuse/mod.rs index 745679d4e72..1431aebc1ff 100644 --- a/esp-hal/src/soc/esp32h2/efuse/mod.rs +++ b/esp-hal/src/soc/esp32h2/efuse/mod.rs @@ -26,9 +26,9 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); -//! # let mut serial_tx = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); +//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32s2/efuse/mod.rs b/esp-hal/src/soc/esp32s2/efuse/mod.rs index 569ce1871ea..67ccf16b873 100644 --- a/esp-hal/src/soc/esp32s2/efuse/mod.rs +++ b/esp-hal/src/soc/esp32s2/efuse/mod.rs @@ -28,9 +28,9 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); -//! # let mut serial_tx = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); +//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32s2/ulp_core.rs b/esp-hal/src/soc/esp32s2/ulp_core.rs index 1e027659c34..6515635347a 100644 --- a/esp-hal/src/soc/esp32s2/ulp_core.rs +++ b/esp-hal/src/soc/esp32s2/ulp_core.rs @@ -19,9 +19,8 @@ //! 0x17, 0x05, 0x00, 0x00, 0x13, 0x05, 0x05, 0x01, 0x81, 0x45, 0x85, 0x05, //! 0x0c, 0xc1, 0xf5, 0xbf, 0x00, 0x00, 0x00, 0x00, //! ]; -//! let system = esp_hal::init(CpuClock::boot_default()); //! let mut ulp_core = -//! esp_hal::ulp_core::UlpCore::new(system.peripherals.ULP_RISCV_CORE); +//! esp_hal::ulp_core::UlpCore::new(peripherals.ULP_RISCV_CORE); //! // ulp_core.stop(); currently not implemented //! //! // copy code to RTC ram diff --git a/esp-hal/src/soc/esp32s3/cpu_control.rs b/esp-hal/src/soc/esp32s3/cpu_control.rs index a9e24e3ada9..be5b2ae03f0 100644 --- a/esp-hal/src/soc/esp32s3/cpu_control.rs +++ b/esp-hal/src/soc/esp32s3/cpu_control.rs @@ -13,14 +13,12 @@ //! # use esp_hal::cpu_control::{CpuControl, Stack}; //! # use core::{cell::RefCell, ptr::addr_of_mut}; //! # use critical_section::Mutex; +//! # let delay = Delay::new(&clocks); //! static mut APP_CORE_STACK: Stack<8192> = Stack::new(); -//! let system = esp_hal::init(CpuClock::boot_default()); -//! -//! # let delay = Delay::new(&system.clocks); //! //! let counter = Mutex::new(RefCell::new(0)); //! -//! let mut cpu_control = CpuControl::new(system.peripherals.CPU_CTRL); +//! let mut cpu_control = CpuControl::new(peripherals.CPU_CTRL); //! let cpu1_fnctn = || { //! cpu1_task(&delay, &counter); //! }; diff --git a/esp-hal/src/soc/esp32s3/efuse/mod.rs b/esp-hal/src/soc/esp32s3/efuse/mod.rs index a73fe786d4e..c4de385dada 100644 --- a/esp-hal/src/soc/esp32s3/efuse/mod.rs +++ b/esp-hal/src/soc/esp32s3/efuse/mod.rs @@ -26,9 +26,9 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); -//! # let mut serial_tx = Uart::new(system.peripherals.UART0, &system.clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); +//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); +//! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32s3/ulp_core.rs b/esp-hal/src/soc/esp32s3/ulp_core.rs index dd92e516431..deae3f75a92 100644 --- a/esp-hal/src/soc/esp32s3/ulp_core.rs +++ b/esp-hal/src/soc/esp32s3/ulp_core.rs @@ -16,15 +16,13 @@ //! //! ```rust, no_run #![doc = crate::before_snippet!()] -//! let system = esp_hal::init(CpuClock::boot_default()); -//! //! const CODE: &[u8] = &[ //! 0x17, 0x05, 0x00, 0x00, 0x13, 0x05, 0x05, 0x01, 0x81, 0x45, 0x85, 0x05, //! 0x0c, 0xc1, 0xf5, 0xbf, 0x00, 0x00, 0x00, 0x00, //! ]; //! //! let mut ulp_core = -//! esp_hal::ulp_core::UlpCore::new(system.peripherals.ULP_RISCV_CORE); +//! esp_hal::ulp_core::UlpCore::new(peripherals.ULP_RISCV_CORE); //! ulp_core.stop(); //! //! // copy code to RTC ram diff --git a/esp-hal/src/spi/master.rs b/esp-hal/src/spi/master.rs index cc529c11ceb..ebd086f79c7 100644 --- a/esp-hal/src/spi/master.rs +++ b/esp-hal/src/spi/master.rs @@ -38,22 +38,20 @@ //! ### SPI Initialization //! ```rust, no_run #![doc = crate::before_snippet!()] -//! # use crate::esp_hal::prelude::_fugit_RateExtU32; //! # use esp_hal::spi::SpiMode; //! # use esp_hal::spi::master::Spi; //! # use esp_hal::gpio::Io; -//! let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! let sclk = io.pins.gpio0; //! let miso = io.pins.gpio2; //! let mosi = io.pins.gpio1; //! let cs = io.pins.gpio5; //! //! let mut spi = Spi::new( -//! system.peripherals.SPI2, +//! peripherals.SPI2, //! 100.kHz(), //! SpiMode::Mode0, -//! &system.clocks, +//! &clocks, //! ) //! .with_pins(Some(sclk), Some(mosi), Some(miso), Some(cs)); //! # } diff --git a/esp-hal/src/spi/slave.rs b/esp-hal/src/spi/slave.rs index 2eabc47ec77..52c3b2eabac 100644 --- a/esp-hal/src/spi/slave.rs +++ b/esp-hal/src/spi/slave.rs @@ -21,11 +21,10 @@ //! # use esp_hal::spi::slave::{prelude::*, Spi}; //! # use esp_hal::dma::Dma; //! # use esp_hal::gpio::Io; -//! let system = esp_hal::init(CpuClock::boot_default()); -//! let dma = Dma::new(system.peripherals.DMA); +//! let dma = Dma::new(peripherals.DMA); #![cfg_attr(esp32s2, doc = "let dma_channel = dma.spi2channel;")] #![cfg_attr(not(esp32s2), doc = "let dma_channel = dma.channel0;")] -//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! let sclk = io.pins.gpio0; //! let miso = io.pins.gpio1; //! let mosi = io.pins.gpio2; @@ -33,7 +32,7 @@ //! //! let (tx_buffer, tx_descriptors, rx_buffer, rx_descriptors) = //! dma_buffers!(32000); let mut spi = Spi::new( -//! system.peripherals.SPI2, +//! peripherals.SPI2, //! sclk, //! mosi, //! miso, diff --git a/esp-hal/src/system.rs b/esp-hal/src/system.rs index 364930a64c2..97086ba4b3c 100755 --- a/esp-hal/src/system.rs +++ b/esp-hal/src/system.rs @@ -19,10 +19,8 @@ //! //! ```rust, no_run #![doc = crate::before_snippet!()] -//! let system = esp_hal::init(CpuClock::boot_default()); -//! //! let sw_ints = -//! SoftwareInterruptControl::new(system.peripherals.SW_INTERRUPT); +//! SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); //! let mut int0 = sw_ints.software_interrupt0; //! //! critical_section::with(|cs| { diff --git a/esp-hal/src/timer/mod.rs b/esp-hal/src/timer/mod.rs index fb7ae3fb146..2e2552684a5 100644 --- a/esp-hal/src/timer/mod.rs +++ b/esp-hal/src/timer/mod.rs @@ -18,8 +18,7 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::timer::{OneShotTimer, PeriodicTimer, timg::TimerGroup}; //! # -//! let system = esp_hal::init(CpuClock::boot_default()); -//! let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); +//! let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); //! let one_shot = OneShotTimer::new(timg0.timer0); //! //! one_shot.delay_millis(500); @@ -31,8 +30,7 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::timer::{PeriodicTimer, timg::TimerGroup}; //! # -//! let system = esp_hal::init(CpuClock::boot_default()); -//! let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); +//! let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); //! let mut periodic = PeriodicTimer::new(timg0.timer0); //! //! periodic.start(1.secs()); diff --git a/esp-hal/src/timer/systimer.rs b/esp-hal/src/timer/systimer.rs index 43ee99807bd..6d33afa35c8 100644 --- a/esp-hal/src/timer/systimer.rs +++ b/esp-hal/src/timer/systimer.rs @@ -28,9 +28,8 @@ //! Periodic, //! }; //! -//! let system = esp_hal::init(CpuClock::boot_default()); //! let systimer = SystemTimer::new( -//! system.peripherals.SYSTIMER, +//! peripherals.SYSTIMER, //! ).split::(); //! //! // Reconfigure a periodic alarm to be a target alarm @@ -48,8 +47,7 @@ //! SystemTimer, //! }; //! -//! let system = esp_hal::init(CpuClock::boot_default()); -//! let mut systimer = SystemTimer::new(system.peripherals.SYSTIMER); +//! let mut systimer = SystemTimer::new(peripherals.SYSTIMER); //! //! // Get the current timestamp, in microseconds: //! let now = SystemTimer::now(); diff --git a/esp-hal/src/timer/timg.rs b/esp-hal/src/timer/timg.rs index 1eb2243f6f5..074252ebbe1 100644 --- a/esp-hal/src/timer/timg.rs +++ b/esp-hal/src/timer/timg.rs @@ -28,8 +28,7 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::timer::timg::TimerGroup; //! -//! let system = esp_hal::init(CpuClock::boot_default()); -//! let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); +//! let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); //! let timer0 = timg0.timer0; //! //! // Get the current timestamp, in microseconds: @@ -52,8 +51,7 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::timer::timg::TimerGroup; //! -//! let system = esp_hal::init(CpuClock::boot_default()); -//! let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); +//! let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); //! let mut wdt = timg0.wdt; //! //! wdt.set_timeout(5_000.millis()); diff --git a/esp-hal/src/twai/mod.rs b/esp-hal/src/twai/mod.rs index b0ebab1dabf..d6e24b5e1ef 100644 --- a/esp-hal/src/twai/mod.rs +++ b/esp-hal/src/twai/mod.rs @@ -35,8 +35,8 @@ //! # use esp_hal::gpio::Io; //! # use embedded_can::Frame; //! # use nb::block; -//! # let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! // Use GPIO pins 2 and 3 to connect to the respective pins on the TWAI //! // transceiver. //! let can_tx_pin = io.pins.gpio2; @@ -48,10 +48,10 @@ //! // Begin configuring the TWAI peripheral. The peripheral is in a reset like //! // state that prevents transmission but allows configuration. //! let mut can_config = twai::TwaiConfiguration::new( -//! system.peripherals.TWAI0, +//! peripherals.TWAI0, //! can_tx_pin, //! can_rx_pin, -//! &system.clocks, +//! &clocks, //! TWAI_BAUDRATE, //! TwaiMode::Normal //! ); @@ -92,8 +92,8 @@ //! # use esp_hal::gpio::Io; //! # use embedded_can::Frame; //! # use nb::block; -//! # let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! // Use GPIO pins 2 and 3 to connect to the respective pins on the TWAI //! // transceiver. //! let can_tx_pin = io.pins.gpio2; @@ -104,10 +104,10 @@ //! //! // Begin configuring the TWAI peripheral. //! let mut can_config = twai::TwaiConfiguration::new( -//! system.peripherals.TWAI0, +//! peripherals.TWAI0, //! can_tx_pin, //! can_rx_pin, -//! &system.clocks, +//! &clocks, //! TWAI_BAUDRATE, //! TwaiMode::SelfTest //! ); diff --git a/esp-hal/src/uart.rs b/esp-hal/src/uart.rs index 0c2b56c6153..9e048fdfa0b 100644 --- a/esp-hal/src/uart.rs +++ b/esp-hal/src/uart.rs @@ -25,12 +25,11 @@ //! # use esp_hal::uart::{config::Config, Uart}; //! use esp_hal::gpio::Io; //! -//! let system = esp_hal::init(CpuClock::boot_default()); -//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! //! let mut uart1 = Uart::new( -//! system.peripherals.UART1, -//! &system.clocks, +//! peripherals.UART1, +//! &clocks, //! io.pins.gpio1, //! io.pins.gpio2, //! ).unwrap(); @@ -59,12 +58,12 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::uart::{config::Config, Uart}; //! # use esp_hal::gpio::Io; -//! # let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut uart1 = Uart::new_with_config( -//! # system.peripherals.UART1, +//! # peripherals.UART1, //! # Config::default(), -//! # &system.clocks, +//! # &clocks, //! # io.pins.gpio1, //! # io.pins.gpio2, //! # ).unwrap(); @@ -78,12 +77,12 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::uart::{config::Config, Uart}; //! # use esp_hal::gpio::Io; -//! # let system = esp_hal::init(CpuClock::boot_default()); -//! # let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut uart1 = Uart::new_with_config( -//! # system.peripherals.UART1, +//! # peripherals.UART1, //! # Config::default(), -//! # &system.clocks, +//! # &clocks, //! # io.pins.gpio1, //! # io.pins.gpio2, //! # ).unwrap(); @@ -102,13 +101,13 @@ //! # use esp_hal::uart::{config::Config, Uart}; //! use esp_hal::gpio::{AnyPin, Io}; //! -//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! //! let tx = AnyPin::new_inverted(io.pins.gpio1); //! let rx = AnyPin::new_inverted(io.pins.gpio2); //! let mut uart1 = Uart::new( -//! system.peripherals.UART1, -//! &system.clocks, +//! peripherals.UART1, +//! &clocks, //! tx, //! rx, //! ).unwrap(); @@ -121,11 +120,11 @@ //! # use esp_hal::uart::{config::Config, UartTx, UartRx}; //! use esp_hal::gpio::{AnyPin, Io}; //! -//! let io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); +//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! -//! let tx = UartTx::new(system.peripherals.UART0, &system.clocks, +//! let tx = UartTx::new(peripherals.UART0, &clocks, //! io.pins.gpio1).unwrap(); -//! let rx = UartRx::new(system.peripherals.UART1, &system.clocks, +//! let rx = UartRx::new(peripherals.UART1, &clocks, //! io.pins.gpio2).unwrap(); //! # } //! ``` diff --git a/esp-hal/src/usb_serial_jtag.rs b/esp-hal/src/usb_serial_jtag.rs index 808bfdc8e08..5e70c0b1199 100644 --- a/esp-hal/src/usb_serial_jtag.rs +++ b/esp-hal/src/usb_serial_jtag.rs @@ -46,8 +46,7 @@ #![doc = crate::before_snippet!()] //! use esp_hal::usb_serial_jtag::UsbSerialJtag; //! -//! let system = esp_hal::init(CpuClock::boot_default()); -//! let mut usb_serial = UsbSerialJtag::new(system.peripherals.USB_DEVICE); +//! let mut usb_serial = UsbSerialJtag::new(peripherals.USB_DEVICE); //! //! // Write bytes out over the USB Serial/JTAG: //! usb_serial.write_bytes(b"Hello, world!").expect("write error!"); @@ -57,10 +56,9 @@ //! ### Splitting the USB Serial/JTAG into TX and RX Components //! ```rust, no_run #![doc = crate::before_snippet!()] -//! # use esp_hal::usb_serial_jtag::UsbSerialJtag; +//! use esp_hal::usb_serial_jtag::UsbSerialJtag; //! -//! let system = esp_hal::init(CpuClock::boot_default()); -//! let mut usb_serial = UsbSerialJtag::new(system.peripherals.USB_DEVICE); +//! let mut usb_serial = UsbSerialJtag::new(peripherals.USB_DEVICE); //! // The USB Serial/JTAG can be split into separate Transmit and Receive //! // components: //! let (mut tx, mut rx) = usb_serial.split(); diff --git a/examples/src/bin/adc.rs b/examples/src/bin/adc.rs index d057ac52627..b145f219905 100644 --- a/examples/src/bin/adc.rs +++ b/examples/src/bin/adc.rs @@ -27,11 +27,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/adc_cal.rs b/examples/src/bin/adc_cal.rs index fcb5afc0b51..c7ad9f8ae06 100644 --- a/examples/src/bin/adc_cal.rs +++ b/examples/src/bin/adc_cal.rs @@ -23,11 +23,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/advanced_serial.rs b/examples/src/bin/advanced_serial.rs index 8575a2d7153..43aeebd572d 100644 --- a/examples/src/bin/advanced_serial.rs +++ b/examples/src/bin/advanced_serial.rs @@ -19,11 +19,7 @@ use nb::block; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/blinky.rs b/examples/src/bin/blinky.rs index 4afe1fa4f8b..9776270975a 100644 --- a/examples/src/bin/blinky.rs +++ b/examples/src/bin/blinky.rs @@ -17,11 +17,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); // Set GPIO0 as an output, and set its state high initially. let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/blinky_erased_pins.rs b/examples/src/bin/blinky_erased_pins.rs index 9a7f219e6e6..1926d42ae5f 100644 --- a/examples/src/bin/blinky_erased_pins.rs +++ b/examples/src/bin/blinky_erased_pins.rs @@ -20,11 +20,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/dac.rs b/examples/src/bin/dac.rs index 16844e69ad7..547a121948f 100644 --- a/examples/src/bin/dac.rs +++ b/examples/src/bin/dac.rs @@ -23,11 +23,7 @@ use esp_hal::{analog::dac::Dac, delay::Delay, gpio::Io, prelude::*}; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/debug_assist.rs b/examples/src/bin/debug_assist.rs index 99345aeb851..b39db5d07b7 100644 --- a/examples/src/bin/debug_assist.rs +++ b/examples/src/bin/debug_assist.rs @@ -18,11 +18,7 @@ static DA: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let mut da = DebugAssist::new(peripherals.ASSIST_DEBUG); da.set_interrupt_handler(interrupt_handler); diff --git a/examples/src/bin/dma_extmem2mem.rs b/examples/src/bin/dma_extmem2mem.rs index 83346f0f0cf..ac4f53fe9a0 100644 --- a/examples/src/bin/dma_extmem2mem.rs +++ b/examples/src/bin/dma_extmem2mem.rs @@ -62,11 +62,7 @@ fn init_heap(psram: impl esp_hal::peripheral::Peripheral

! { esp_println::logger::init_logger(log::LevelFilter::Info); - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); init_heap(peripherals.PSRAM); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/dma_mem2mem.rs b/examples/src/bin/dma_mem2mem.rs index e4606010ae1..3a32335800c 100644 --- a/examples/src/bin/dma_mem2mem.rs +++ b/examples/src/bin/dma_mem2mem.rs @@ -21,11 +21,7 @@ const DATA_SIZE: usize = 1024 * 10; fn main() -> ! { esp_println::logger::init_logger(log::LevelFilter::Info); - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/embassy_hello_world.rs b/examples/src/bin/embassy_hello_world.rs index 7eea9c96362..61d6cd9524c 100644 --- a/examples/src/bin/embassy_hello_world.rs +++ b/examples/src/bin/embassy_hello_world.rs @@ -25,11 +25,7 @@ async fn run() { #[esp_hal_embassy::main] async fn main(spawner: Spawner) { esp_println::logger::init_logger_from_env(); - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); esp_println::println!("Init!"); diff --git a/examples/src/bin/embassy_i2c.rs b/examples/src/bin/embassy_i2c.rs index a6d703763e8..e471357ea83 100644 --- a/examples/src/bin/embassy_i2c.rs +++ b/examples/src/bin/embassy_i2c.rs @@ -24,11 +24,7 @@ use lis3dh_async::{Lis3dh, Range, SlaveAddr}; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs b/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs index 9537856f413..ccd27614d79 100644 --- a/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs +++ b/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs @@ -24,11 +24,7 @@ use esp_hal::{gpio::Io, i2c::I2C, prelude::*, timer::timg::TimerGroup}; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_i2s_read.rs b/examples/src/bin/embassy_i2s_read.rs index 4c2c80d9e18..7be3b82ce30 100644 --- a/examples/src/bin/embassy_i2s_read.rs +++ b/examples/src/bin/embassy_i2s_read.rs @@ -32,11 +32,7 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { println!("Init!"); - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_i2s_sound.rs b/examples/src/bin/embassy_i2s_sound.rs index 8c54d1ce44e..e21cb747d8d 100644 --- a/examples/src/bin/embassy_i2s_sound.rs +++ b/examples/src/bin/embassy_i2s_sound.rs @@ -54,11 +54,7 @@ const SINE: [i16; 64] = [ #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { println!("Init!"); - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_multicore.rs b/examples/src/bin/embassy_multicore.rs index cfc5a704c61..2d5797a954b 100644 --- a/examples/src/bin/embassy_multicore.rs +++ b/examples/src/bin/embassy_multicore.rs @@ -51,11 +51,7 @@ async fn control_led( #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/embassy_multicore_interrupt.rs b/examples/src/bin/embassy_multicore_interrupt.rs index ed469647765..97a2fb210c6 100644 --- a/examples/src/bin/embassy_multicore_interrupt.rs +++ b/examples/src/bin/embassy_multicore_interrupt.rs @@ -22,8 +22,8 @@ use esp_hal::{ get_core, gpio::{AnyOutput, Io, Level}, interrupt::Priority, - system::SoftwareInterruptControl, prelude::*, + system::SoftwareInterruptControl, timer::{timg::TimerGroup, ErasedTimer}, }; use esp_hal_embassy::InterruptExecutor; @@ -72,10 +72,7 @@ async fn enable_disable_led(control: &'static Signal ! { - let System { - peripherals, - clocks, - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); @@ -94,8 +91,7 @@ fn main() -> ! { let led = AnyOutput::new(io.pins.gpio0, Level::Low); static EXECUTOR_CORE_1: StaticCell> = StaticCell::new(); - let executor_core1 = - InterruptExecutor::new(sw_ints.software_interrupt1); + let executor_core1 = InterruptExecutor::new(sw_ints.software_interrupt1); let executor_core1 = EXECUTOR_CORE_1.init(executor_core1); let _guard = cpu_control @@ -110,8 +106,7 @@ fn main() -> ! { .unwrap(); static EXECUTOR_CORE_0: StaticCell> = StaticCell::new(); - let executor_core0 = - InterruptExecutor::new(sw_ints.software_interrupt0); + let executor_core0 = InterruptExecutor::new(sw_ints.software_interrupt0); let executor_core0 = EXECUTOR_CORE_0.init(executor_core0); let spawner = executor_core0.start(Priority::Priority1); diff --git a/examples/src/bin/embassy_multiprio.rs b/examples/src/bin/embassy_multiprio.rs index c28349daea9..eb272bbcdff 100644 --- a/examples/src/bin/embassy_multiprio.rs +++ b/examples/src/bin/embassy_multiprio.rs @@ -72,10 +72,7 @@ async fn main(low_prio_spawner: Spawner) { esp_println::logger::init_logger_from_env(); println!("Init!"); - let System { - peripherals, - clocks, - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); diff --git a/examples/src/bin/embassy_parl_io_rx.rs b/examples/src/bin/embassy_parl_io_rx.rs index 03393706f98..66177788669 100644 --- a/examples/src/bin/embassy_parl_io_rx.rs +++ b/examples/src/bin/embassy_parl_io_rx.rs @@ -26,11 +26,7 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let systimer = SystemTimer::new(peripherals.SYSTIMER).split::(); esp_hal_embassy::init(&clocks, systimer.alarm0); diff --git a/examples/src/bin/embassy_parl_io_tx.rs b/examples/src/bin/embassy_parl_io_tx.rs index 2b5f96a8814..5d56050770d 100644 --- a/examples/src/bin/embassy_parl_io_tx.rs +++ b/examples/src/bin/embassy_parl_io_tx.rs @@ -37,11 +37,7 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let systimer = SystemTimer::new(peripherals.SYSTIMER).split::(); esp_hal_embassy::init(&clocks, systimer.alarm0); diff --git a/examples/src/bin/embassy_rmt_rx.rs b/examples/src/bin/embassy_rmt_rx.rs index 4c91b896fcc..b0e958206b7 100644 --- a/examples/src/bin/embassy_rmt_rx.rs +++ b/examples/src/bin/embassy_rmt_rx.rs @@ -39,11 +39,7 @@ async fn signal_task(mut pin: Output<'static, Gpio5>) { #[esp_hal_embassy::main] async fn main(spawner: Spawner) { println!("Init!"); - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_rmt_tx.rs b/examples/src/bin/embassy_rmt_tx.rs index 8b2e43fbf42..8ab6c589f19 100644 --- a/examples/src/bin/embassy_rmt_tx.rs +++ b/examples/src/bin/embassy_rmt_tx.rs @@ -25,12 +25,7 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { println!("Init!"); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_serial.rs b/examples/src/bin/embassy_serial.rs index 28cbc8d8a5b..250d716bc69 100644 --- a/examples/src/bin/embassy_serial.rs +++ b/examples/src/bin/embassy_serial.rs @@ -78,11 +78,7 @@ async fn reader( #[esp_hal_embassy::main] async fn main(spawner: Spawner) { esp_println::println!("Init!"); - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_spi.rs b/examples/src/bin/embassy_spi.rs index 19f3bf939f5..24a0e4b47cb 100644 --- a/examples/src/bin/embassy_spi.rs +++ b/examples/src/bin/embassy_spi.rs @@ -33,11 +33,7 @@ use esp_hal::{ #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_touch.rs b/examples/src/bin/embassy_touch.rs index 33399587ae6..524255cd8d4 100644 --- a/examples/src/bin/embassy_touch.rs +++ b/examples/src/bin/embassy_touch.rs @@ -27,12 +27,7 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_twai.rs b/examples/src/bin/embassy_twai.rs index deb3a40c55d..53435d2f279 100644 --- a/examples/src/bin/embassy_twai.rs +++ b/examples/src/bin/embassy_twai.rs @@ -82,11 +82,7 @@ async fn transmitter( #[esp_hal_embassy::main] async fn main(spawner: Spawner) { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_usb_serial.rs b/examples/src/bin/embassy_usb_serial.rs index 670eb07e42e..47ab396cca9 100644 --- a/examples/src/bin/embassy_usb_serial.rs +++ b/examples/src/bin/embassy_usb_serial.rs @@ -32,11 +32,7 @@ use esp_hal::{ #[esp_hal_embassy::main] async fn main(_spawner: Spawner) -> () { esp_println::println!("Init!"); - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_usb_serial_jtag.rs b/examples/src/bin/embassy_usb_serial_jtag.rs index c537305edc7..af4f8e3d89f 100644 --- a/examples/src/bin/embassy_usb_serial_jtag.rs +++ b/examples/src/bin/embassy_usb_serial_jtag.rs @@ -63,11 +63,7 @@ async fn reader( #[esp_hal_embassy::main] async fn main(spawner: Spawner) -> () { esp_println::println!("Init!"); - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_wait.rs b/examples/src/bin/embassy_wait.rs index a366f2adf9a..2db9b2cbd27 100644 --- a/examples/src/bin/embassy_wait.rs +++ b/examples/src/bin/embassy_wait.rs @@ -19,11 +19,7 @@ use esp_hal::{ #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/etm_blinky_systimer.rs b/examples/src/bin/etm_blinky_systimer.rs index bc8f56eacb7..6e0fcbdff42 100644 --- a/examples/src/bin/etm_blinky_systimer.rs +++ b/examples/src/bin/etm_blinky_systimer.rs @@ -24,7 +24,7 @@ use fugit::ExtU32; #[entry] fn main() -> ! { - let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); let syst = SystemTimer::new(peripherals.SYSTIMER); let syst_alarms = syst.split::(); diff --git a/examples/src/bin/etm_gpio.rs b/examples/src/bin/etm_gpio.rs index 0f4f874a59f..c11beed9003 100644 --- a/examples/src/bin/etm_gpio.rs +++ b/examples/src/bin/etm_gpio.rs @@ -22,7 +22,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let mut led = io.pins.gpio1; diff --git a/examples/src/bin/etm_timer.rs b/examples/src/bin/etm_timer.rs index 5d752415194..2650f223559 100644 --- a/examples/src/bin/etm_timer.rs +++ b/examples/src/bin/etm_timer.rs @@ -28,11 +28,7 @@ static TIMER0: Mutex, esp_hal::Blocking>>>> = #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); let timer0 = timg0.timer0; diff --git a/examples/src/bin/gpio_interrupt.rs b/examples/src/bin/gpio_interrupt.rs index 1d5211d136e..b8efe82a01e 100644 --- a/examples/src/bin/gpio_interrupt.rs +++ b/examples/src/bin/gpio_interrupt.rs @@ -32,11 +32,7 @@ cfg_if::cfg_if! { #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); // Set GPIO2 as an output, and set its state high initially. let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/hello_rgb.rs b/examples/src/bin/hello_rgb.rs index 125ab2f6ac2..a2095e99d81 100644 --- a/examples/src/bin/hello_rgb.rs +++ b/examples/src/bin/hello_rgb.rs @@ -36,11 +36,7 @@ use smart_leds::{ #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/hello_world.rs b/examples/src/bin/hello_world.rs index c844955f4d0..0126d62259c 100644 --- a/examples/src/bin/hello_world.rs +++ b/examples/src/bin/hello_world.rs @@ -19,11 +19,7 @@ use esp_hal::{delay::Delay, gpio::Io, prelude::*, uart::Uart}; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/hmac.rs b/examples/src/bin/hmac.rs index d4c520b2830..8c1f16d0529 100644 --- a/examples/src/bin/hmac.rs +++ b/examples/src/bin/hmac.rs @@ -73,7 +73,7 @@ type HmacSha256 = HmacSw; #[entry] fn main() -> ! { - let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); let mut rng = Rng::new(peripherals.RNG); diff --git a/examples/src/bin/i2c_bmp180_calibration_data.rs b/examples/src/bin/i2c_bmp180_calibration_data.rs index f80ba7b0c57..f0995b795f8 100644 --- a/examples/src/bin/i2c_bmp180_calibration_data.rs +++ b/examples/src/bin/i2c_bmp180_calibration_data.rs @@ -17,11 +17,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/i2c_display.rs b/examples/src/bin/i2c_display.rs index c9332482747..90e3ed64e22 100644 --- a/examples/src/bin/i2c_display.rs +++ b/examples/src/bin/i2c_display.rs @@ -28,11 +28,7 @@ use ssd1306::{prelude::*, I2CDisplayInterface, Ssd1306}; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/i2s_read.rs b/examples/src/bin/i2s_read.rs index ecf20f1ff6b..21c5c7b4c54 100644 --- a/examples/src/bin/i2s_read.rs +++ b/examples/src/bin/i2s_read.rs @@ -28,11 +28,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/i2s_sound.rs b/examples/src/bin/i2s_sound.rs index cee33aa8454..4eb64a2737b 100644 --- a/examples/src/bin/i2s_sound.rs +++ b/examples/src/bin/i2s_sound.rs @@ -49,11 +49,7 @@ const SINE: [i16; 64] = [ #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/ieee802154_receive_all_frames.rs b/examples/src/bin/ieee802154_receive_all_frames.rs index 63283096c28..a1b2897f012 100644 --- a/examples/src/bin/ieee802154_receive_all_frames.rs +++ b/examples/src/bin/ieee802154_receive_all_frames.rs @@ -10,7 +10,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); let mut ieee802154 = Ieee802154::new(peripherals.IEEE802154, &mut peripherals.RADIO_CLK); ieee802154.set_config(Config { diff --git a/examples/src/bin/ieee802154_receive_frame.rs b/examples/src/bin/ieee802154_receive_frame.rs index 8d8cc9a7a97..de4ceccaf95 100644 --- a/examples/src/bin/ieee802154_receive_frame.rs +++ b/examples/src/bin/ieee802154_receive_frame.rs @@ -10,9 +10,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - mut peripherals, .. - } = esp_hal::init(CpuClock::boot_default()); + let (mut peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); let mut ieee802154 = Ieee802154::new(peripherals.IEEE802154, &mut peripherals.RADIO_CLK); ieee802154.set_config(Config { diff --git a/examples/src/bin/ieee802154_send_broadcast_frame.rs b/examples/src/bin/ieee802154_send_broadcast_frame.rs index cb6c3f83e2f..92b7a2c1210 100644 --- a/examples/src/bin/ieee802154_send_broadcast_frame.rs +++ b/examples/src/bin/ieee802154_send_broadcast_frame.rs @@ -19,11 +19,7 @@ use ieee802154::mac::{ #[entry] fn main() -> ! { - let System { - mut peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (mut peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/ieee802154_send_frame.rs b/examples/src/bin/ieee802154_send_frame.rs index 0b58de65f59..78a8b2b9bdc 100644 --- a/examples/src/bin/ieee802154_send_frame.rs +++ b/examples/src/bin/ieee802154_send_frame.rs @@ -19,11 +19,7 @@ use ieee802154::mac::{ #[entry] fn main() -> ! { - let System { - mut peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (mut peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/ieee802154_sniffer.rs b/examples/src/bin/ieee802154_sniffer.rs index f6adeea22af..bd5d0d69778 100644 --- a/examples/src/bin/ieee802154_sniffer.rs +++ b/examples/src/bin/ieee802154_sniffer.rs @@ -14,11 +14,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - mut peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (mut peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/lcd_cam_ov2640.rs b/examples/src/bin/lcd_cam_ov2640.rs index 66af3da963e..24f5cffbed5 100644 --- a/examples/src/bin/lcd_cam_ov2640.rs +++ b/examples/src/bin/lcd_cam_ov2640.rs @@ -42,11 +42,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/lcd_i8080.rs b/examples/src/bin/lcd_i8080.rs index f332e1c3b48..8d60cd76998 100644 --- a/examples/src/bin/lcd_i8080.rs +++ b/examples/src/bin/lcd_i8080.rs @@ -37,11 +37,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/ledc.rs b/examples/src/bin/ledc.rs index 197e488b972..c0649053f00 100644 --- a/examples/src/bin/ledc.rs +++ b/examples/src/bin/ledc.rs @@ -24,11 +24,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let led = io.pins.gpio0; diff --git a/examples/src/bin/lp_core_basic.rs b/examples/src/bin/lp_core_basic.rs index a86affe6ca9..815bb8ebf8a 100644 --- a/examples/src/bin/lp_core_basic.rs +++ b/examples/src/bin/lp_core_basic.rs @@ -23,7 +23,7 @@ use esp_println::{print, println}; #[entry] fn main() -> ! { - let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); // configure GPIO 1 as LP output pin let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/lp_core_i2c.rs b/examples/src/bin/lp_core_i2c.rs index b384f91a5d1..e0188b9577e 100644 --- a/examples/src/bin/lp_core_i2c.rs +++ b/examples/src/bin/lp_core_i2c.rs @@ -25,7 +25,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/lp_core_uart.rs b/examples/src/bin/lp_core_uart.rs index 5ca98a3e743..279cf24ed11 100644 --- a/examples/src/bin/lp_core_uart.rs +++ b/examples/src/bin/lp_core_uart.rs @@ -28,11 +28,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/mcpwm.rs b/examples/src/bin/mcpwm.rs index aa1c0dc53bf..2cd0c8fe8a7 100644 --- a/examples/src/bin/mcpwm.rs +++ b/examples/src/bin/mcpwm.rs @@ -18,11 +18,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let pin = io.pins.gpio0; diff --git a/examples/src/bin/multicore.rs b/examples/src/bin/multicore.rs index da1c30bfcb5..3ce24dee0dd 100644 --- a/examples/src/bin/multicore.rs +++ b/examples/src/bin/multicore.rs @@ -23,11 +23,7 @@ static mut APP_CORE_STACK: Stack<8192> = Stack::new(); #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/parl_io_rx.rs b/examples/src/bin/parl_io_rx.rs index 1ac2a674653..89996729dc7 100644 --- a/examples/src/bin/parl_io_rx.rs +++ b/examples/src/bin/parl_io_rx.rs @@ -22,11 +22,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/parl_io_tx.rs b/examples/src/bin/parl_io_tx.rs index 21350a45b96..ab95783deed 100644 --- a/examples/src/bin/parl_io_tx.rs +++ b/examples/src/bin/parl_io_tx.rs @@ -33,11 +33,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/pcnt_encoder.rs b/examples/src/bin/pcnt_encoder.rs index c97eb848699..7a2d9029e3d 100644 --- a/examples/src/bin/pcnt_encoder.rs +++ b/examples/src/bin/pcnt_encoder.rs @@ -37,7 +37,7 @@ static VALUE: AtomicI32 = AtomicI32::new(0); #[entry] fn main() -> ! { - let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/psram_octal.rs b/examples/src/bin/psram_octal.rs index 9f1be148c08..b7aa1225863 100644 --- a/examples/src/bin/psram_octal.rs +++ b/examples/src/bin/psram_octal.rs @@ -30,7 +30,7 @@ fn main() -> ! { #[cfg(debug_assertions)] compile_error!("This example MUST be built in release mode!"); - let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); psram::init_psram(peripherals.PSRAM); init_psram_heap(); diff --git a/examples/src/bin/psram_quad.rs b/examples/src/bin/psram_quad.rs index 7a4eb58d2c2..88b03467d20 100644 --- a/examples/src/bin/psram_quad.rs +++ b/examples/src/bin/psram_quad.rs @@ -30,7 +30,7 @@ fn main() -> ! { #[cfg(debug_assertions)] compile_error!("PSRAM example must be built in release mode!"); - let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); psram::init_psram(peripherals.PSRAM); init_psram_heap(); diff --git a/examples/src/bin/qspi_flash.rs b/examples/src/bin/qspi_flash.rs index 7d575a14878..d6e57e036b6 100644 --- a/examples/src/bin/qspi_flash.rs +++ b/examples/src/bin/qspi_flash.rs @@ -44,11 +44,7 @@ use esp_println::{print, println}; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/ram.rs b/examples/src/bin/ram.rs index d5218a644a4..b45b1cd1d45 100644 --- a/examples/src/bin/ram.rs +++ b/examples/src/bin/ram.rs @@ -31,11 +31,7 @@ static mut SOME_ZEROED_DATA: [u8; 8] = [0; 8]; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/rmt_rx.rs b/examples/src/bin/rmt_rx.rs index 6bda14a9988..6c55dc1aa19 100644 --- a/examples/src/bin/rmt_rx.rs +++ b/examples/src/bin/rmt_rx.rs @@ -24,11 +24,7 @@ const WIDTH: usize = 80; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let mut out = io.pins.gpio5; diff --git a/examples/src/bin/rmt_tx.rs b/examples/src/bin/rmt_tx.rs index eb1e556c568..6ae28c27221 100644 --- a/examples/src/bin/rmt_tx.rs +++ b/examples/src/bin/rmt_tx.rs @@ -20,11 +20,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/rng.rs b/examples/src/bin/rng.rs index 2fb85892846..d69920fb336 100644 --- a/examples/src/bin/rng.rs +++ b/examples/src/bin/rng.rs @@ -11,7 +11,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); let mut rng = Rng::new(peripherals.RNG); // Generate a random word (u32): diff --git a/examples/src/bin/rtc_time.rs b/examples/src/bin/rtc_time.rs index 8a30b8aa3d6..5d93ec4b196 100644 --- a/examples/src/bin/rtc_time.rs +++ b/examples/src/bin/rtc_time.rs @@ -10,11 +10,7 @@ use esp_hal::{delay::Delay, prelude::*, rtc_cntl::Rtc}; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let rtc = Rtc::new(peripherals.LPWR); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/rtc_watchdog.rs b/examples/src/bin/rtc_watchdog.rs index 47fbee2fe47..4beb8991543 100644 --- a/examples/src/bin/rtc_watchdog.rs +++ b/examples/src/bin/rtc_watchdog.rs @@ -24,7 +24,7 @@ static RWDT: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { - let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); let mut rtc = Rtc::new(peripherals.LPWR); rtc.set_interrupt_handler(interrupt_handler); diff --git a/examples/src/bin/serial_interrupts.rs b/examples/src/bin/serial_interrupts.rs index 22ebb78e4e9..9d8a48da265 100644 --- a/examples/src/bin/serial_interrupts.rs +++ b/examples/src/bin/serial_interrupts.rs @@ -27,11 +27,7 @@ static SERIAL: Mutex>>> = Mutex::new(RefCel #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/sleep_timer.rs b/examples/src/bin/sleep_timer.rs index 19c6eaf2abc..07464fcf6f4 100644 --- a/examples/src/bin/sleep_timer.rs +++ b/examples/src/bin/sleep_timer.rs @@ -18,11 +18,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_ext0.rs b/examples/src/bin/sleep_timer_ext0.rs index 56b47302a8b..f6608cd71d5 100644 --- a/examples/src/bin/sleep_timer_ext0.rs +++ b/examples/src/bin/sleep_timer_ext0.rs @@ -28,11 +28,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_ext1.rs b/examples/src/bin/sleep_timer_ext1.rs index e2a5602140e..9c7687f4f52 100644 --- a/examples/src/bin/sleep_timer_ext1.rs +++ b/examples/src/bin/sleep_timer_ext1.rs @@ -28,11 +28,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_lpio.rs b/examples/src/bin/sleep_timer_lpio.rs index cd1b6de2dd6..f76a5e0d0ef 100644 --- a/examples/src/bin/sleep_timer_lpio.rs +++ b/examples/src/bin/sleep_timer_lpio.rs @@ -29,11 +29,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_rtcio.rs b/examples/src/bin/sleep_timer_rtcio.rs index 74b7e97165c..ed8bbad6a6a 100644 --- a/examples/src/bin/sleep_timer_rtcio.rs +++ b/examples/src/bin/sleep_timer_rtcio.rs @@ -33,11 +33,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/software_interrupts.rs b/examples/src/bin/software_interrupts.rs index 8cae314f47c..6f7c13e2b26 100644 --- a/examples/src/bin/software_interrupts.rs +++ b/examples/src/bin/software_interrupts.rs @@ -26,11 +26,7 @@ static SWINT3: Mutex>>> = Mutex::new(RefCell #[entry] fn main() -> ! { - let System { - clocks, - peripherals, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let mut sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); diff --git a/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs b/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs index e0a01e1c3ce..20a2e9bd81b 100644 --- a/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs +++ b/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs @@ -42,11 +42,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/spi_loopback.rs b/examples/src/bin/spi_loopback.rs index d9f2d11b598..b0a37b23bfb 100644 --- a/examples/src/bin/spi_loopback.rs +++ b/examples/src/bin/spi_loopback.rs @@ -29,11 +29,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/examples/src/bin/spi_loopback_dma.rs b/examples/src/bin/spi_loopback_dma.rs index 454a3286ecd..3b2e7b3579f 100644 --- a/examples/src/bin/spi_loopback_dma.rs +++ b/examples/src/bin/spi_loopback_dma.rs @@ -34,11 +34,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/examples/src/bin/spi_slave_dma.rs b/examples/src/bin/spi_slave_dma.rs index 2070b000b1d..42242b96e60 100644 --- a/examples/src/bin/spi_slave_dma.rs +++ b/examples/src/bin/spi_slave_dma.rs @@ -45,11 +45,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let slave_sclk = io.pins.gpio0; diff --git a/examples/src/bin/systimer.rs b/examples/src/bin/systimer.rs index 05b11715e7f..122c96cb088 100644 --- a/examples/src/bin/systimer.rs +++ b/examples/src/bin/systimer.rs @@ -47,11 +47,7 @@ static ALARM2: Mutex< #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let systimer = SystemTimer::new(peripherals.SYSTIMER); println!("SYSTIMER Current value = {}", SystemTimer::now()); diff --git a/examples/src/bin/timer_interrupt.rs b/examples/src/bin/timer_interrupt.rs index fe78ef8fb6b..5adec94ab72 100644 --- a/examples/src/bin/timer_interrupt.rs +++ b/examples/src/bin/timer_interrupt.rs @@ -23,11 +23,7 @@ static TIMER0: Mutex, esp_hal::Blocking>>>> = #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); let timer0 = timg0.timer0; diff --git a/examples/src/bin/touch.rs b/examples/src/bin/touch.rs index 5a7d69e7c99..6c00245b7e3 100644 --- a/examples/src/bin/touch.rs +++ b/examples/src/bin/touch.rs @@ -48,11 +48,7 @@ fn interrupt_handler() { #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/twai.rs b/examples/src/bin/twai.rs index 546b978d3db..a32b69b1f29 100644 --- a/examples/src/bin/twai.rs +++ b/examples/src/bin/twai.rs @@ -35,11 +35,7 @@ use nb::block; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/ulp_riscv_core_basic.rs b/examples/src/bin/ulp_riscv_core_basic.rs index 5477b94d671..ac09e536ab6 100644 --- a/examples/src/bin/ulp_riscv_core_basic.rs +++ b/examples/src/bin/ulp_riscv_core_basic.rs @@ -21,7 +21,7 @@ use esp_println::{print, println}; #[entry] fn main() -> ! { - let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let pin = LowPowerOutput::new(io.pins.gpio1); diff --git a/examples/src/bin/usb_serial.rs b/examples/src/bin/usb_serial.rs index fc3cbde68a7..3719fbc9508 100644 --- a/examples/src/bin/usb_serial.rs +++ b/examples/src/bin/usb_serial.rs @@ -26,7 +26,7 @@ static mut EP_MEMORY: [u32; 1024] = [0; 1024]; #[entry] fn main() -> ! { - let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/usb_serial_jtag.rs b/examples/src/bin/usb_serial_jtag.rs index a79dfbc11be..06687a13c34 100644 --- a/examples/src/bin/usb_serial_jtag.rs +++ b/examples/src/bin/usb_serial_jtag.rs @@ -23,11 +23,7 @@ static USB_SERIAL: Mutex>>> = #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/watchdog.rs b/examples/src/bin/watchdog.rs index 9813f620fd7..03b61ecd4b8 100644 --- a/examples/src/bin/watchdog.rs +++ b/examples/src/bin/watchdog.rs @@ -14,11 +14,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/wifi_80211_tx.rs b/examples/src/bin/wifi_80211_tx.rs index 59ecc0a05a9..0010e1b4553 100644 --- a/examples/src/bin/wifi_80211_tx.rs +++ b/examples/src/bin/wifi_80211_tx.rs @@ -34,12 +34,7 @@ const MAC_ADDRESS: [u8; 6] = [0x00, 0x80, 0x41, 0x13, 0x37, 0x42]; #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/wifi_access_point.rs b/examples/src/bin/wifi_access_point.rs index b394e91ca19..2f56f3792f5 100644 --- a/examples/src/bin/wifi_access_point.rs +++ b/examples/src/bin/wifi_access_point.rs @@ -34,12 +34,7 @@ use smoltcp::iface::SocketStorage; #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_access_point_with_sta.rs b/examples/src/bin/wifi_access_point_with_sta.rs index 8e09695fb5d..72e1e2a9b8e 100644 --- a/examples/src/bin/wifi_access_point_with_sta.rs +++ b/examples/src/bin/wifi_access_point_with_sta.rs @@ -41,12 +41,7 @@ const PASSWORD: &str = env!("PASSWORD"); #[entry] fn main() -> ! { esp_println::logger::init_logger(log::LevelFilter::Info); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_bench.rs b/examples/src/bin/wifi_bench.rs index 2f688e4ab06..429a27ed5c8 100644 --- a/examples/src/bin/wifi_bench.rs +++ b/examples/src/bin/wifi_bench.rs @@ -51,12 +51,7 @@ const UPLOAD_DOWNLOAD_PORT: u16 = 4323; #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let server_address: Ipv4Address = HOST_IP.parse().expect("Invalid HOST_IP address"); diff --git a/examples/src/bin/wifi_ble.rs b/examples/src/bin/wifi_ble.rs index 8ac846a5b11..f5f2010841c 100644 --- a/examples/src/bin/wifi_ble.rs +++ b/examples/src/bin/wifi_ble.rs @@ -36,12 +36,7 @@ use esp_wifi::{ble::controller::BleConnector, initialize, EspWifiInitFor}; #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_coex.rs b/examples/src/bin/wifi_coex.rs index 084cca7059b..7087ac24c00 100644 --- a/examples/src/bin/wifi_coex.rs +++ b/examples/src/bin/wifi_coex.rs @@ -47,12 +47,7 @@ const PASSWORD: &str = env!("PASSWORD"); #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_dhcp.rs b/examples/src/bin/wifi_dhcp.rs index 8814172b782..74fea7ca852 100644 --- a/examples/src/bin/wifi_dhcp.rs +++ b/examples/src/bin/wifi_dhcp.rs @@ -40,12 +40,7 @@ const PASSWORD: &str = env!("PASSWORD"); #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_access_point.rs b/examples/src/bin/wifi_embassy_access_point.rs index ad33af13cba..bdfc63a4a42 100644 --- a/examples/src/bin/wifi_embassy_access_point.rs +++ b/examples/src/bin/wifi_embassy_access_point.rs @@ -56,12 +56,7 @@ macro_rules! mk_static { #[esp_hal_embassy::main] async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_access_point_with_sta.rs b/examples/src/bin/wifi_embassy_access_point_with_sta.rs index 220707fbb85..5cb2a7dd5c1 100644 --- a/examples/src/bin/wifi_embassy_access_point_with_sta.rs +++ b/examples/src/bin/wifi_embassy_access_point_with_sta.rs @@ -70,12 +70,7 @@ macro_rules! mk_static { #[esp_hal_embassy::main] async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_bench.rs b/examples/src/bin/wifi_embassy_bench.rs index 5031f7cb09a..5bf9823020c 100644 --- a/examples/src/bin/wifi_embassy_bench.rs +++ b/examples/src/bin/wifi_embassy_bench.rs @@ -66,12 +66,7 @@ static mut TX_BUFFER: [u8; TX_BUFFER_SIZE] = [0; TX_BUFFER_SIZE]; #[esp_hal_embassy::main] async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let server_address: Ipv4Address = HOST_IP.parse().expect("Invalid HOST_IP address"); diff --git a/examples/src/bin/wifi_embassy_ble.rs b/examples/src/bin/wifi_embassy_ble.rs index 054926eae4e..d54c99516b9 100644 --- a/examples/src/bin/wifi_embassy_ble.rs +++ b/examples/src/bin/wifi_embassy_ble.rs @@ -38,12 +38,7 @@ use esp_wifi::{ble::controller::asynch::BleConnector, initialize, EspWifiInitFor #[esp_hal_embassy::main] async fn main(_spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_dhcp.rs b/examples/src/bin/wifi_embassy_dhcp.rs index 15146591e65..3c371cafdd2 100644 --- a/examples/src/bin/wifi_embassy_dhcp.rs +++ b/examples/src/bin/wifi_embassy_dhcp.rs @@ -49,12 +49,7 @@ const PASSWORD: &str = env!("PASSWORD"); #[esp_hal_embassy::main] async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_esp_now.rs b/examples/src/bin/wifi_embassy_esp_now.rs index f93916981a6..031b97cd62c 100644 --- a/examples/src/bin/wifi_embassy_esp_now.rs +++ b/examples/src/bin/wifi_embassy_esp_now.rs @@ -25,12 +25,7 @@ use esp_wifi::{ #[esp_hal_embassy::main] async fn main(_spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_esp_now_duplex.rs b/examples/src/bin/wifi_embassy_esp_now_duplex.rs index 59c43eaba90..7d7cf4b8ae4 100644 --- a/examples/src/bin/wifi_embassy_esp_now_duplex.rs +++ b/examples/src/bin/wifi_embassy_esp_now_duplex.rs @@ -35,12 +35,7 @@ macro_rules! mk_static { #[esp_hal_embassy::main] async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_esp_now.rs b/examples/src/bin/wifi_esp_now.rs index 1e539415d06..f3bc86beb85 100644 --- a/examples/src/bin/wifi_esp_now.rs +++ b/examples/src/bin/wifi_esp_now.rs @@ -21,12 +21,7 @@ use esp_wifi::{ #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_sniffer.rs b/examples/src/bin/wifi_sniffer.rs index b8b27b589cb..38f005a61fd 100644 --- a/examples/src/bin/wifi_sniffer.rs +++ b/examples/src/bin/wifi_sniffer.rs @@ -33,12 +33,7 @@ static KNOWN_SSIDS: Mutex>> = Mutex::new(RefCell::new(B #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); // Create a heap allocator, with 32kB of space. heap_allocator!(32_168); diff --git a/examples/src/bin/wifi_static_ip.rs b/examples/src/bin/wifi_static_ip.rs index 4075c8749c0..41b9547ad03 100644 --- a/examples/src/bin/wifi_static_ip.rs +++ b/examples/src/bin/wifi_static_ip.rs @@ -40,12 +40,7 @@ const GATEWAY_IP: &str = env!("GATEWAY_IP"); #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init(CpuClock::max()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/hil-test/tests/aes.rs b/hil-test/tests/aes.rs index ffcc1d23e0c..4b2cc35332a 100644 --- a/hil-test/tests/aes.rs +++ b/hil-test/tests/aes.rs @@ -17,7 +17,7 @@ struct Context<'a> { impl Context<'_> { pub fn init() -> Self { - let System { peripherals, .. } = esp_hal::init(CpuClock::max()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::max()); let aes = Aes::new(peripherals.AES); Context { aes } diff --git a/hil-test/tests/aes_dma.rs b/hil-test/tests/aes_dma.rs index 67c596dcdae..70bc9d5caec 100644 --- a/hil-test/tests/aes_dma.rs +++ b/hil-test/tests/aes_dma.rs @@ -29,8 +29,8 @@ mod tests { #[init] fn init() -> Peripherals { - let system = esp_hal::init(CpuClock::boot_default()); - system.peripherals + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + peripherals } #[test] diff --git a/hil-test/tests/clock_monitor.rs b/hil-test/tests/clock_monitor.rs index cfa7e9de3e0..54004ffa583 100644 --- a/hil-test/tests/clock_monitor.rs +++ b/hil-test/tests/clock_monitor.rs @@ -14,8 +14,8 @@ struct Context<'a> { impl Context<'_> { pub fn init() -> Self { - let system = esp_hal::init(CpuClock::boot_default()); - let rtc = Rtc::new(system.peripherals.LPWR); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let rtc = Rtc::new(peripherals.LPWR); Context { rtc } } diff --git a/hil-test/tests/delay.rs b/hil-test/tests/delay.rs index 8e5854a2c90..698ea65f97a 100644 --- a/hil-test/tests/delay.rs +++ b/hil-test/tests/delay.rs @@ -15,8 +15,8 @@ struct Context { impl Context { pub fn init() -> Self { - let system = esp_hal::init(CpuClock::boot_default()); - let delay = Delay::new(&system.clocks); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let delay = Delay::new(&clocks); Context { delay } } diff --git a/hil-test/tests/dma_mem2mem.rs b/hil-test/tests/dma_mem2mem.rs index bb960f204bf..d612711d617 100644 --- a/hil-test/tests/dma_mem2mem.rs +++ b/hil-test/tests/dma_mem2mem.rs @@ -39,16 +39,16 @@ mod tests { #[init] fn init() -> Context { - let system = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); - let dma = Dma::new(system.peripherals.DMA); + let dma = Dma::new(peripherals.DMA); let channel = dma.channel0.configure(false, DmaPriority::Priority0); cfg_if::cfg_if! { if #[cfg(any(feature = "esp32c2", feature = "esp32c3", feature = "esp32s3"))] { - let dma_peripheral = system.peripherals.SPI2; + let dma_peripheral = peripherals.SPI2; } else { - let dma_peripheral = system.peripherals.MEM2MEM1; + let dma_peripheral = peripherals.MEM2MEM1; } } diff --git a/hil-test/tests/ecc.rs b/hil-test/tests/ecc.rs index 5e4cb64f6e7..4f785152189 100644 --- a/hil-test/tests/ecc.rs +++ b/hil-test/tests/ecc.rs @@ -56,7 +56,7 @@ mod tests { #[init] fn init() -> Context<'static> { - let System { peripherals, .. } = esp_hal::init(CpuClock::max()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::max()); let ecc = Ecc::new(peripherals.ECC); let rng = Rng::new(peripherals.RNG); diff --git a/hil-test/tests/embassy_interrupt_executor.rs b/hil-test/tests/embassy_interrupt_executor.rs index da440e10587..aa88037a6dc 100644 --- a/hil-test/tests/embassy_interrupt_executor.rs +++ b/hil-test/tests/embassy_interrupt_executor.rs @@ -43,7 +43,7 @@ mod test { #[init] fn init() -> SoftwareInterrupt<1> { - let System{peripherals,..} = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/hil-test/tests/embassy_timers_executors.rs b/hil-test/tests/embassy_timers_executors.rs index 61026762374..a6b8a9f504c 100644 --- a/hil-test/tests/embassy_timers_executors.rs +++ b/hil-test/tests/embassy_timers_executors.rs @@ -8,17 +8,19 @@ #![no_main] use embassy_time::{Duration, Ticker, Timer}; -#[cfg(not(feature = "esp32"))] -use esp_hal::{ - interrupt::Priority, - timer::systimer::{Alarm, FrozenUnit, Periodic, SystemTimer, Target}, -}; use esp_hal::{ + clock::Clocks, + peripherals::Peripherals, prelude::*, system::SoftwareInterruptControl, timer::{timg::TimerGroup, ErasedTimer, OneShotTimer, PeriodicTimer}, }; #[cfg(not(feature = "esp32"))] +use esp_hal::{ + interrupt::Priority, + timer::systimer::{Alarm, FrozenUnit, Periodic, SystemTimer, Target}, +}; +#[cfg(not(feature = "esp32"))] use esp_hal_embassy::InterruptExecutor; use hil_test as _; @@ -107,15 +109,15 @@ mod test_cases { } } -fn set_up_embassy_with_timg0(system: System) { - let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); - esp_hal_embassy::init(&system.clocks, timg0.timer0); +fn set_up_embassy_with_timg0(peripherals: Peripherals, clocks: Clocks<'static>) { + let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); + esp_hal_embassy::init(&clocks, timg0.timer0); } #[cfg(not(feature = "esp32"))] -fn set_up_embassy_with_systimer(system: System) { - let systimer = SystemTimer::new(system.peripherals.SYSTIMER).split::(); - esp_hal_embassy::init(&system.clocks, systimer.alarm0); +fn set_up_embassy_with_systimer(peripherals: Peripherals, clocks: Clocks<'static>) { + let systimer = SystemTimer::new(peripherals.SYSTIMER).split::(); + esp_hal_embassy::init(&clocks, systimer.alarm0); } #[cfg(test)] @@ -125,14 +127,14 @@ mod test { use crate::{test_cases::*, test_helpers::*}; #[init] - fn init() -> System { + fn init() -> (Peripherals, Clocks<'static>) { esp_hal::init(CpuClock::boot_default()) } #[test] #[timeout(3)] - async fn test_one_shot_timg(system: System) { - set_up_embassy_with_timg0(system); + async fn test_one_shot_timg((peripherals, clocks): (Peripherals, Clocks<'static>)) { + set_up_embassy_with_timg0(peripherals, clocks); run_test_one_shot_async().await; } @@ -140,16 +142,16 @@ mod test { #[test] #[timeout(3)] #[cfg(not(feature = "esp32"))] - async fn test_one_shot_systimer(system: System) { - set_up_embassy_with_systimer(system); + async fn test_one_shot_systimer((peripherals, clocks): (Peripherals, Clocks<'static>)) { + set_up_embassy_with_systimer(peripherals, clocks); run_test_one_shot_async().await; } #[test] #[timeout(3)] - fn test_periodic_timg(system: System) { - let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); + fn test_periodic_timg((peripherals, clocks): (Peripherals, Clocks<'static>)) { + let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); run_test_periodic_timer(timg0.timer0); } @@ -157,32 +159,32 @@ mod test { #[test] #[timeout(3)] #[cfg(not(feature = "esp32"))] - fn test_periodic_systimer(system: System) { - let systimer = SystemTimer::new(system.peripherals.SYSTIMER).split::(); + fn test_periodic_systimer((peripherals, clocks): (Peripherals, Clocks<'static>)) { + let systimer = SystemTimer::new(peripherals.SYSTIMER).split::(); run_test_periodic_timer(systimer.alarm0); } #[test] #[timeout(3)] - fn test_periodic_oneshot_timg(mut system: System) { - let mut timg0 = TimerGroup::new(&mut system.peripherals.TIMG0, &system.clocks); + fn test_periodic_oneshot_timg((mut peripherals, clocks): (Peripherals, Clocks<'static>)) { + let mut timg0 = TimerGroup::new(&mut peripherals.TIMG0, &clocks); run_test_periodic_timer(&mut timg0.timer0); - let mut timg0 = TimerGroup::new(&mut system.peripherals.TIMG0, &system.clocks); + let mut timg0 = TimerGroup::new(&mut peripherals.TIMG0, &clocks); run_test_oneshot_timer(&mut timg0.timer0); } #[test] #[timeout(3)] #[cfg(not(feature = "esp32"))] - fn test_periodic_oneshot_systimer(mut system: System) { - let mut systimer = SystemTimer::new(&mut system.peripherals.SYSTIMER); + fn test_periodic_oneshot_systimer((mut peripherals, clocks): (Peripherals, Clocks<'static>)) { + let mut systimer = SystemTimer::new(&mut peripherals.SYSTIMER); let unit = FrozenUnit::new(&mut systimer.unit0); let mut alarm: Alarm<'_, Periodic, _, _, _> = Alarm::new(systimer.comparator0, &unit); run_test_periodic_timer(&mut alarm); - let mut systimer = SystemTimer::new(&mut system.peripherals.SYSTIMER); + let mut systimer = SystemTimer::new(&mut peripherals.SYSTIMER); let unit = FrozenUnit::new(&mut systimer.unit0); let mut alarm: Alarm<'_, Target, _, _, _> = Alarm::new(systimer.comparator0, &unit); run_test_oneshot_timer(&mut alarm); @@ -190,8 +192,8 @@ mod test { #[test] #[timeout(3)] - async fn test_join_timg(system: System) { - set_up_embassy_with_timg0(system); + async fn test_join_timg((peripherals, clocks): (Peripherals, Clocks<'static>)) { + set_up_embassy_with_timg0(peripherals, clocks); run_join_test().await; } @@ -199,8 +201,8 @@ mod test { #[test] #[timeout(3)] #[cfg(not(feature = "esp32"))] - async fn test_join_systimer(system: System) { - set_up_embassy_with_systimer(system); + async fn test_join_systimer((peripherals, clocks): (Peripherals, Clocks<'static>)) { + set_up_embassy_with_systimer(peripherals, clocks); run_join_test().await; } @@ -209,19 +211,19 @@ mod test { #[test] #[timeout(3)] #[cfg(not(feature = "esp32"))] - async fn test_interrupt_executor(system: System) { - let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); + async fn test_interrupt_executor((peripherals, clocks): (Peripherals, Clocks<'static>)) { + let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); let timer0: ErasedTimer = timg0.timer0.into(); let timer0 = OneShotTimer::new(timer0); - let systimer = SystemTimer::new(system.peripherals.SYSTIMER).split::(); + let systimer = SystemTimer::new(peripherals.SYSTIMER).split::(); let alarm0: ErasedTimer = systimer.alarm0.into(); let timer1 = OneShotTimer::new(alarm0); let timers = mk_static!([OneShotTimer; 2], [timer0, timer1]); - esp_hal_embassy::init(&system.clocks, timers); + esp_hal_embassy::init(&clocks, timers); - let sw_ints = SoftwareInterruptControl::new(system.peripherals.SW_INTERRUPT); + let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); let executor = mk_static!( InterruptExecutor<2>, @@ -264,8 +266,8 @@ mod test { /// Test that timg0 and systimer don't have vastly different tick rates. #[test] #[timeout(3)] - async fn tick_test_timer_tick_rates(system: System) { - set_up_embassy_with_timg0(system); + async fn tick_test_timer_tick_rates((peripherals, clocks): (Peripherals, Clocks<'static>)) { + set_up_embassy_with_timg0(peripherals, clocks); // We are retrying 5 times because probe-rs polling RTT may introduce some // jitter. diff --git a/hil-test/tests/get_time.rs b/hil-test/tests/get_time.rs index 5511c564825..59b918e4897 100644 --- a/hil-test/tests/get_time.rs +++ b/hil-test/tests/get_time.rs @@ -35,7 +35,7 @@ mod tests { #[init] fn init() -> Context { - let system = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let delay = Delay::new(&system.clocks); diff --git a/hil-test/tests/gpio.rs b/hil-test/tests/gpio.rs index 4281e4cfc8c..e6ececfc256 100644 --- a/hil-test/tests/gpio.rs +++ b/hil-test/tests/gpio.rs @@ -34,15 +34,15 @@ struct Context<'d> { impl<'d> Context<'d> { pub fn init() -> Self { - let system = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); - let mut io = Io::new(system.peripherals.GPIO, system.peripherals.IO_MUX); + let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); io.set_interrupt_handler(interrupt_handler); - let delay = Delay::new(&system.clocks); + let delay = Delay::new(&clocks); - let timg0 = TimerGroup::new(system.peripherals.TIMG0, &system.clocks); - esp_hal_embassy::init(&system.clocks, timg0.timer0); + let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); + esp_hal_embassy::init(&clocks, timg0.timer0); Context { io2: Input::new(io.pins.gpio2, Pull::Down), diff --git a/hil-test/tests/i2s.rs b/hil-test/tests/i2s.rs index fd282ea3098..20918b4b389 100644 --- a/hil-test/tests/i2s.rs +++ b/hil-test/tests/i2s.rs @@ -53,10 +53,10 @@ mod tests { #[test] fn test_i2s_loopback() { - let system = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); - let peripherals = system.peripherals; - let clocks = system.clocks; + let peripherals = peripherals; + let clocks = clocks; let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/i2s_async.rs b/hil-test/tests/i2s_async.rs index ead6e40c572..75a543fc50f 100644 --- a/hil-test/tests/i2s_async.rs +++ b/hil-test/tests/i2s_async.rs @@ -85,10 +85,10 @@ mod tests { async fn test_i2s_loopback() { let spawner = embassy_executor::Spawner::for_current_executor().await; - let system = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); - let peripherals = system.peripherals; - let clocks = system.clocks; + let peripherals = peripherals; + let clocks = clocks; let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/interrupt.rs b/hil-test/tests/interrupt.rs index b8b76f5e03d..5e7d2d66ae9 100644 --- a/hil-test/tests/interrupt.rs +++ b/hil-test/tests/interrupt.rs @@ -25,37 +25,6 @@ struct Context { sw0_trigger_addr: u32, } -impl Context { - pub fn init() -> Self { - let System { peripherals, .. } = esp_hal::init(CpuClock::max()); - let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); - - cfg_if::cfg_if! { - if #[cfg(any(feature = "esp32c6", feature = "esp32h2"))] { - let cpu_intr = &peripherals.INTPRI; - } else { - let cpu_intr = &peripherals.SYSTEM; - } - } - - let sw0_trigger_addr = cpu_intr.cpu_intr_from_cpu_0() as *const _ as u32; - - critical_section::with(|cs| { - SWINT0 - .borrow_ref_mut(cs) - .replace(sw_ints.software_interrupt0) - }); - interrupt::enable_direct( - Interrupt::FROM_CPU_INTR0, - Priority::Priority3, - CpuInterrupt::Interrupt20, - ) - .unwrap(); - - Context { sw0_trigger_addr } - } -} - #[no_mangle] fn interrupt20() { unsafe { asm!("csrrwi x0, 0x7e1, 0 #disable timer") } @@ -91,7 +60,32 @@ mod tests { #[init] fn init() -> Context { - Context::init() + let (peripherals, _clocks) = esp_hal::init(CpuClock::max()); + let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); + + cfg_if::cfg_if! { + if #[cfg(any(feature = "esp32c6", feature = "esp32h2"))] { + let cpu_intr = &peripherals.INTPRI; + } else { + let cpu_intr = &peripherals.SYSTEM; + } + } + + let sw0_trigger_addr = cpu_intr.cpu_intr_from_cpu_0() as *const _ as u32; + + critical_section::with(|cs| { + SWINT0 + .borrow_ref_mut(cs) + .replace(sw_ints.software_interrupt0) + }); + interrupt::enable_direct( + Interrupt::FROM_CPU_INTR0, + Priority::Priority3, + CpuInterrupt::Interrupt20, + ) + .unwrap(); + + Context { sw0_trigger_addr } } #[test] diff --git a/hil-test/tests/lcd_cam_i8080.rs b/hil-test/tests/lcd_cam_i8080.rs index 22d1238066c..02281df1e2f 100644 --- a/hil-test/tests/lcd_cam_i8080.rs +++ b/hil-test/tests/lcd_cam_i8080.rs @@ -35,11 +35,7 @@ mod tests { #[init] fn init() -> Context<'static> { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let dma = Dma::new(peripherals.DMA); let lcd_cam = LcdCam::new(peripherals.LCD_CAM); let (tx_buffer, tx_descriptors, _, _) = dma_buffers!(DATA_SIZE, 0); diff --git a/hil-test/tests/lcd_cam_i8080_async.rs b/hil-test/tests/lcd_cam_i8080_async.rs index 9d82a64dc0d..ee8c86168ff 100644 --- a/hil-test/tests/lcd_cam_i8080_async.rs +++ b/hil-test/tests/lcd_cam_i8080_async.rs @@ -39,11 +39,7 @@ mod tests { #[init] async fn init() -> Context<'static> { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let dma = Dma::new(peripherals.DMA); let lcd_cam = LcdCam::new_async(peripherals.LCD_CAM); diff --git a/hil-test/tests/pcnt.rs b/hil-test/tests/pcnt.rs index 0ae11fb2d62..17c70b94a54 100644 --- a/hil-test/tests/pcnt.rs +++ b/hil-test/tests/pcnt.rs @@ -32,11 +32,7 @@ mod tests { #[init] fn init() -> Context<'static> { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/rmt.rs b/hil-test/tests/rmt.rs index 5595651a15b..5c50f307f96 100644 --- a/hil-test/tests/rmt.rs +++ b/hil-test/tests/rmt.rs @@ -25,11 +25,7 @@ mod tests { #[test] #[timeout(1)] fn rmt_loopback() { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/rsa.rs b/hil-test/tests/rsa.rs index ae73767d45a..59deac571ee 100644 --- a/hil-test/tests/rsa.rs +++ b/hil-test/tests/rsa.rs @@ -57,7 +57,7 @@ mod tests { #[init] fn init() -> Context<'static> { - let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); let mut rsa = Rsa::new(peripherals.RSA); nb::block!(rsa.ready()).unwrap(); diff --git a/hil-test/tests/sha.rs b/hil-test/tests/sha.rs index 50047f21680..47888c792f0 100644 --- a/hil-test/tests/sha.rs +++ b/hil-test/tests/sha.rs @@ -166,9 +166,9 @@ mod tests { cfg_if::cfg_if! { if #[cfg(feature = "esp32")] { // FIXME: max speed fails...? - let System { peripherals, .. } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); } else { - let System { peripherals, .. } = esp_hal::init(CpuClock::max()); + let (peripherals, _clocks) = esp_hal::init(CpuClock::max()); } } diff --git a/hil-test/tests/spi_full_duplex.rs b/hil-test/tests/spi_full_duplex.rs index 89515a63de9..9865db9a017 100644 --- a/hil-test/tests/spi_full_duplex.rs +++ b/hil-test/tests/spi_full_duplex.rs @@ -34,11 +34,7 @@ mod tests { #[init] fn init() -> Context { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/spi_full_duplex_dma.rs b/hil-test/tests/spi_full_duplex_dma.rs index d7f3e07a71c..28e0737ee5d 100644 --- a/hil-test/tests/spi_full_duplex_dma.rs +++ b/hil-test/tests/spi_full_duplex_dma.rs @@ -14,7 +14,7 @@ #![no_main] use esp_hal::{ - clock::ClockControl, + clock::{ClockControl, Clocks}, dma::{Dma, DmaPriority, DmaRxBuf, DmaTxBuf}, dma_buffers, gpio::Io, @@ -55,11 +55,7 @@ mod tests { #[init] fn init() -> Context { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/spi_full_duplex_dma_async.rs b/hil-test/tests/spi_full_duplex_dma_async.rs index ac91128dc52..e4f0b485145 100644 --- a/hil-test/tests/spi_full_duplex_dma_async.rs +++ b/hil-test/tests/spi_full_duplex_dma_async.rs @@ -22,7 +22,7 @@ use embedded_hal_async::spi::SpiBus; use esp_hal::{ - clock::ClockControl, + clock::{ClockControl, Clocks}, dma::{Dma, DmaPriority, DmaRxBuf, DmaTxBuf}, dma_buffers, gpio::{GpioPin, Io, Level, Output, Pull}, @@ -72,11 +72,7 @@ mod tests { #[init] fn init() -> Context { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let pcnt = Pcnt::new(peripherals.PCNT); diff --git a/hil-test/tests/spi_half_duplex_read.rs b/hil-test/tests/spi_half_duplex_read.rs index e30be14a97e..c4bfb75c097 100644 --- a/hil-test/tests/spi_half_duplex_read.rs +++ b/hil-test/tests/spi_half_duplex_read.rs @@ -56,11 +56,7 @@ mod tests { #[init] fn init() -> Context { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/spi_half_duplex_write.rs b/hil-test/tests/spi_half_duplex_write.rs index daa88004233..137b0fd0a39 100644 --- a/hil-test/tests/spi_half_duplex_write.rs +++ b/hil-test/tests/spi_half_duplex_write.rs @@ -65,11 +65,7 @@ mod tests { #[init] fn init() -> Context { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/systimer.rs b/hil-test/tests/systimer.rs index 3b0116c48ca..c419e5503ef 100644 --- a/hil-test/tests/systimer.rs +++ b/hil-test/tests/systimer.rs @@ -104,11 +104,7 @@ mod tests { #[init] fn init() -> Context { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let systimer = SystemTimer::new(peripherals.SYSTIMER); static UNIT0: StaticCell> = StaticCell::new(); diff --git a/hil-test/tests/twai.rs b/hil-test/tests/twai.rs index efc6df74962..40f9844b96f 100644 --- a/hil-test/tests/twai.rs +++ b/hil-test/tests/twai.rs @@ -35,11 +35,7 @@ mod tests { #[init] fn init() -> Context { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/uart.rs b/hil-test/tests/uart.rs index 06fc2f122fa..51398f2d10f 100644 --- a/hil-test/tests/uart.rs +++ b/hil-test/tests/uart.rs @@ -37,11 +37,7 @@ mod tests { #[init] fn init() -> Context { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/uart_async.rs b/hil-test/tests/uart_async.rs index 43e3c632fdb..a674d6ee3c0 100644 --- a/hil-test/tests/uart_async.rs +++ b/hil-test/tests/uart_async.rs @@ -28,11 +28,7 @@ mod tests { #[init] async fn init() -> Context { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/uart_tx_rx.rs b/hil-test/tests/uart_tx_rx.rs index a9b2f494f06..b5cc88d5560 100644 --- a/hil-test/tests/uart_tx_rx.rs +++ b/hil-test/tests/uart_tx_rx.rs @@ -35,11 +35,7 @@ mod tests { #[init] fn init() -> Context { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/uart_tx_rx_async.rs b/hil-test/tests/uart_tx_rx_async.rs index 01aedbbf661..5c6ba5b6f84 100644 --- a/hil-test/tests/uart_tx_rx_async.rs +++ b/hil-test/tests/uart_tx_rx_async.rs @@ -35,11 +35,7 @@ mod tests { #[init] async fn init() -> Context { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/usb_serial_jtag.rs b/hil-test/tests/usb_serial_jtag.rs index e4a582ba0c4..2b51317dbbb 100644 --- a/hil-test/tests/usb_serial_jtag.rs +++ b/hil-test/tests/usb_serial_jtag.rs @@ -13,11 +13,7 @@ mod tests { #[test] fn creating_peripheral_does_not_break_debug_connection() { - let System { - peripherals, - clocks, - .. - } = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); From e2eab66bbadd8acc396a4eba45afa5c09fa975a3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Fri, 23 Aug 2024 10:36:16 +0200 Subject: [PATCH 04/19] Fix docs --- esp-hal/src/delay.rs | 1 + esp-hal/src/lib.rs | 16 ++++++---------- esp-hal/src/timer/systimer.rs | 2 +- 3 files changed, 8 insertions(+), 11 deletions(-) diff --git a/esp-hal/src/delay.rs b/esp-hal/src/delay.rs index 2b55786c455..c15c6e66ae6 100644 --- a/esp-hal/src/delay.rs +++ b/esp-hal/src/delay.rs @@ -31,6 +31,7 @@ //! [DelayMs]: embedded_hal_02::blocking::delay::DelayMs //! [DelayUs]: embedded_hal_02::blocking::delay::DelayUs //! [embedded-hal]: https://docs.rs/embedded-hal/1.0.0/embedded_hal/delay/index.html +//! [current_time]: crate::time::current_time pub use fugit::MicrosDurationU64; diff --git a/esp-hal/src/lib.rs b/esp-hal/src/lib.rs index aff3813dc7b..783e38eaf45 100644 --- a/esp-hal/src/lib.rs +++ b/esp-hal/src/lib.rs @@ -60,17 +60,16 @@ //! #![no_std] //! #![no_main] //! -//! // A panic - handler e.g. `use esp_backtrace as _;` -//! +//! // You'll need a panic handler e.g. `use esp_backtrace as _;` +//! # #[panic_handler] +//! # fn panic(_ : &core::panic::PanicInfo) -> ! { +//! # loop {} +//! # } //! use esp_hal::{ //! delay::Delay, //! gpio::{Io, Level, Output}, //! prelude::*, //! }; -//! # #[panic_handler] -//! # fn panic(_ : &core::panic::PanicInfo) -> ! { -//! # loop {} -//! # } //! //! #[entry] //! fn main() -> ! { @@ -90,10 +89,7 @@ //! ``` //! //! The steps here are: -//! - Take all the peripherals from the PAC to pass them to the HAL drivers -//! later -//! - Create [system::SystemControl] -//! - Configure the system clocks - in this case use the boot defaults +//! - Call [`init`] with the desired [`CpuClock`] configuration //! - Create [gpio::Io] which provides access to the GPIO pins //! - Create an [gpio::Output] pin driver which lets us control the logical //! level of an output pin diff --git a/esp-hal/src/timer/systimer.rs b/esp-hal/src/timer/systimer.rs index 6d33afa35c8..b740c9877e3 100644 --- a/esp-hal/src/timer/systimer.rs +++ b/esp-hal/src/timer/systimer.rs @@ -18,7 +18,7 @@ //! //! ### Splitting up the System Timer into three alarms //! -//! Use the [split] method to create three alarms from the System Timer, +//! Use the [split][SystemTimer::split] method to create three alarms from the System Timer, //! contained in a [SysTimerAlarms] struct. //! //! ```rust, no_run From 88e738e99aa43b493ef653aefc6aae0557519cb1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Fri, 23 Aug 2024 10:45:04 +0200 Subject: [PATCH 05/19] Remove SystemClockControl --- esp-hal/src/lib.rs | 6 +++--- esp-hal/src/system.rs | 45 ++++++++++++------------------------------- 2 files changed, 15 insertions(+), 36 deletions(-) diff --git a/esp-hal/src/lib.rs b/esp-hal/src/lib.rs index 783e38eaf45..10c040d5b26 100644 --- a/esp-hal/src/lib.rs +++ b/esp-hal/src/lib.rs @@ -90,10 +90,10 @@ //! //! The steps here are: //! - Call [`init`] with the desired [`CpuClock`] configuration -//! - Create [gpio::Io] which provides access to the GPIO pins -//! - Create an [gpio::Output] pin driver which lets us control the logical +//! - Create [`gpio::Io`] which provides access to the GPIO pins +//! - Create an [`gpio::Output`] pin driver which lets us control the logical //! level of an output pin -//! - Create a [delay::Delay] driver +//! - Create a [`delay::Delay`] driver //! - In a loop, toggle the output pin's logical level with a delay of 1000 ms //! //! ## `PeripheralRef` Pattern diff --git a/esp-hal/src/system.rs b/esp-hal/src/system.rs index 97086ba4b3c..5fbc9029e92 100755 --- a/esp-hal/src/system.rs +++ b/esp-hal/src/system.rs @@ -21,24 +21,32 @@ #![doc = crate::before_snippet!()] //! let sw_ints = //! SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); +//! +//! // Take the interrupt you want to use. //! let mut int0 = sw_ints.software_interrupt0; //! +//! // Set up the interrupt handler. Do this in a critical section so the global +//! // contains the interrupt object before the interrupt is triggered. //! critical_section::with(|cs| { //! int0.set_interrupt_handler(interrupt_handler); //! SWINT0.borrow_ref_mut(cs).replace(int0); //! }); //! # } //! -//! use core::cell::RefCell; -//! use critical_section::Mutex; -//! use esp_hal::system::{SoftwareInterrupt, SoftwareInterruptControl}; +//! # use core::cell::RefCell; +//! # use critical_section::Mutex; +//! # use esp_hal::system::{SoftwareInterrupt, SoftwareInterruptControl}; +//! // ... somewhere outside of your main function //! +//! // Define a shared handle to the software interrupt. //! static SWINT0: Mutex>>> = //! Mutex::new(RefCell::new(None)); //! //! #[handler] //! fn interrupt_handler() { -//! // esp_println::println!("SW interrupt0"); +//! // esp_println::println!("SW interrupt0 handled"); +//! +//! // Clear the interrupt request. //! critical_section::with(|cs| { //! SWINT0.borrow_ref(cs).as_ref().unwrap().reset(); //! }); @@ -1177,35 +1185,6 @@ impl PeripheralClockControl { } } -/// Controls the configuration of the chip's clocks. -pub struct SystemClockControl { - _private: (), -} - -impl SystemClockControl { - /// Creates new instance of `SystemClockControl`. - pub fn new() -> Self { - Self { _private: () } - } -} - -impl Default for SystemClockControl { - fn default() -> Self { - Self::new() - } -} - -impl crate::peripheral::Peripheral for SystemClockControl { - type P = SystemClockControl; - - #[inline] - unsafe fn clone_unchecked(&mut self) -> Self::P { - SystemClockControl { _private: () } - } -} - -impl crate::private::Sealed for SystemClockControl {} - /// Enumeration of the available radio peripherals for this chip. #[cfg(any(bt, ieee802154, wifi))] pub enum RadioPeripherals { From 1e0beabb40aa7403b6f571ec9a6d634f51f4bb72 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Mon, 26 Aug 2024 11:23:47 +0200 Subject: [PATCH 06/19] Move software interrupts under interrupt --- esp-hal-embassy/src/executor/interrupt.rs | 3 +- esp-hal-embassy/src/executor/mod.rs | 2 +- esp-hal-embassy/src/executor/thread.rs | 2 +- esp-hal/src/interrupt/mod.rs | 4 +- esp-hal/src/interrupt/software.rs | 206 +++++++++++++++++++ esp-hal/src/system.rs | 201 +----------------- esp-hal/src/timer/systimer.rs | 4 +- examples/src/bin/software_interrupts.rs | 2 +- hil-test/tests/embassy_interrupt_executor.rs | 2 +- hil-test/tests/interrupt.rs | 6 +- 10 files changed, 221 insertions(+), 211 deletions(-) create mode 100644 esp-hal/src/interrupt/software.rs diff --git a/esp-hal-embassy/src/executor/interrupt.rs b/esp-hal-embassy/src/executor/interrupt.rs index 89369a81c8a..8dcc343e9fd 100644 --- a/esp-hal-embassy/src/executor/interrupt.rs +++ b/esp-hal-embassy/src/executor/interrupt.rs @@ -5,8 +5,7 @@ use core::{cell::UnsafeCell, mem::MaybeUninit}; use embassy_executor::{raw, SendSpawner}; use esp_hal::{ get_core, - interrupt::{self, InterruptHandler}, - system::SoftwareInterrupt, + interrupt::{self, software::SoftwareInterrupt, InterruptHandler}, }; use portable_atomic::{AtomicUsize, Ordering}; diff --git a/esp-hal-embassy/src/executor/mod.rs b/esp-hal-embassy/src/executor/mod.rs index f82bf3f6c43..51e43f34e79 100644 --- a/esp-hal-embassy/src/executor/mod.rs +++ b/esp-hal-embassy/src/executor/mod.rs @@ -5,7 +5,7 @@ mod thread; #[export_name = "__pender"] fn __pender(context: *mut ()) { - use esp_hal::system::SoftwareInterrupt; + use esp_hal::interrupt::software::SoftwareInterrupt; let context = (context as usize).to_le_bytes(); diff --git a/esp-hal-embassy/src/executor/thread.rs b/esp-hal-embassy/src/executor/thread.rs index e21c837001c..5050a3793c1 100644 --- a/esp-hal-embassy/src/executor/thread.rs +++ b/esp-hal-embassy/src/executor/thread.rs @@ -77,7 +77,7 @@ This will use software-interrupt 3 which isn't available for anything else to wa pub fn new() -> Self { #[cfg(multi_core)] unsafe { - esp_hal::system::SoftwareInterrupt::<3>::steal() + esp_hal::interrupt::software::SoftwareInterrupt::<3>::steal() .set_interrupt_handler(software3_interrupt) } diff --git a/esp-hal/src/interrupt/mod.rs b/esp-hal/src/interrupt/mod.rs index 9d60824f080..b71b9757f93 100644 --- a/esp-hal/src/interrupt/mod.rs +++ b/esp-hal/src/interrupt/mod.rs @@ -51,7 +51,7 @@ //! # use core::cell::RefCell; //! # //! # use critical_section::Mutex; -//! # use esp_hal::system::{SoftwareInterrupt, SoftwareInterruptControl}; +//! # use esp_hal::interrupt::software::{SoftwareInterrupt, SoftwareInterruptControl}; //! # use esp_hal::interrupt::Priority; //! # use esp_hal::interrupt::InterruptHandler; //! # @@ -79,6 +79,8 @@ mod riscv; #[cfg(xtensa)] mod xtensa; +pub mod software; + /// An interrupt handler #[cfg_attr( multi_core, diff --git a/esp-hal/src/interrupt/software.rs b/esp-hal/src/interrupt/software.rs new file mode 100644 index 00000000000..e707e1d742a --- /dev/null +++ b/esp-hal/src/interrupt/software.rs @@ -0,0 +1,206 @@ +//! # Software Interrupts +//! +//! The `SoftwareInterruptControl` struct gives access to the available software +//! interrupts. +//! +//! The `SoftwareInterrupt` struct allows raising or resetting software +//! interrupts using the `raise()` and `reset()` methods. +//! +//! ## Examples +//! +//! ```rust, no_run +#![doc = crate::before_snippet!()] +//! let sw_ints = +//! SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); +//! +//! // Take the interrupt you want to use. +//! let mut int0 = sw_ints.software_interrupt0; +//! +//! // Set up the interrupt handler. Do this in a critical section so the global +//! // contains the interrupt object before the interrupt is triggered. +//! critical_section::with(|cs| { +//! int0.set_interrupt_handler(interrupt_handler); +//! SWINT0.borrow_ref_mut(cs).replace(int0); +//! }); +//! # } +//! +//! # use core::cell::RefCell; +//! # use critical_section::Mutex; +//! # use esp_hal::interrupt::software::{SoftwareInterrupt, SoftwareInterruptControl}; +//! // ... somewhere outside of your main function +//! +//! // Define a shared handle to the software interrupt. +//! static SWINT0: Mutex>>> = +//! Mutex::new(RefCell::new(None)); +//! +//! #[handler] +//! fn interrupt_handler() { +//! // esp_println::println!("SW interrupt0 handled"); +//! +//! // Clear the interrupt request. +//! critical_section::with(|cs| { +//! SWINT0.borrow_ref(cs).as_ref().unwrap().reset(); +//! }); +//! } +//! ``` + +use crate::{interrupt::InterruptHandler, peripherals::SYSTEM, InterruptConfigurable}; + +/// A software interrupt can be triggered by software. +#[non_exhaustive] +pub struct SoftwareInterrupt; + +impl SoftwareInterrupt { + /// Sets the interrupt handler for this software-interrupt + pub fn set_interrupt_handler(&mut self, handler: InterruptHandler) { + let interrupt = match NUM { + 0 => crate::peripherals::Interrupt::FROM_CPU_INTR0, + 1 => crate::peripherals::Interrupt::FROM_CPU_INTR1, + 2 => crate::peripherals::Interrupt::FROM_CPU_INTR2, + 3 => crate::peripherals::Interrupt::FROM_CPU_INTR3, + _ => unreachable!(), + }; + + unsafe { + crate::interrupt::bind_interrupt(interrupt, handler.handler()); + crate::interrupt::enable(interrupt, handler.priority()).unwrap(); + } + } + + /// Trigger this software-interrupt + pub fn raise(&self) { + cfg_if::cfg_if! { + if #[cfg(any(esp32c6, esp32h2))] { + let system = unsafe { &*crate::peripherals::INTPRI::PTR }; + } else { + let system = unsafe { &*SYSTEM::PTR }; + } + } + + match NUM { + 0 => { + system + .cpu_intr_from_cpu_0() + .write(|w| w.cpu_intr_from_cpu_0().set_bit()); + } + 1 => { + system + .cpu_intr_from_cpu_1() + .write(|w| w.cpu_intr_from_cpu_1().set_bit()); + } + 2 => { + system + .cpu_intr_from_cpu_2() + .write(|w| w.cpu_intr_from_cpu_2().set_bit()); + } + 3 => { + system + .cpu_intr_from_cpu_3() + .write(|w| w.cpu_intr_from_cpu_3().set_bit()); + } + _ => unreachable!(), + } + } + + /// Resets this software-interrupt + pub fn reset(&self) { + cfg_if::cfg_if! { + if #[cfg(any(esp32c6, esp32h2))] { + let system = unsafe { &*crate::peripherals::INTPRI::PTR }; + } else { + let system = unsafe { &*SYSTEM::PTR }; + } + } + + match NUM { + 0 => { + system + .cpu_intr_from_cpu_0() + .write(|w| w.cpu_intr_from_cpu_0().clear_bit()); + } + 1 => { + system + .cpu_intr_from_cpu_1() + .write(|w| w.cpu_intr_from_cpu_1().clear_bit()); + } + 2 => { + system + .cpu_intr_from_cpu_2() + .write(|w| w.cpu_intr_from_cpu_2().clear_bit()); + } + 3 => { + system + .cpu_intr_from_cpu_3() + .write(|w| w.cpu_intr_from_cpu_3().clear_bit()); + } + _ => unreachable!(), + } + } + + /// Unsafely create an instance of this peripheral out of thin air. + /// + /// # Safety + /// + /// You must ensure that you're only using one instance of this type at a + /// time. + #[inline] + pub unsafe fn steal() -> Self { + Self + } +} + +impl crate::peripheral::Peripheral for SoftwareInterrupt { + type P = SoftwareInterrupt; + + #[inline] + unsafe fn clone_unchecked(&mut self) -> Self::P { + Self::steal() + } +} + +impl crate::private::Sealed for SoftwareInterrupt {} + +impl InterruptConfigurable for SoftwareInterrupt { + fn set_interrupt_handler(&mut self, handler: crate::interrupt::InterruptHandler) { + SoftwareInterrupt::set_interrupt_handler(self, handler); + } +} + +/// This gives access to the available software interrupts. +/// +/// This struct contains several instances of software interrupts that can be +/// used for signaling between different parts of a program or system. Each +/// interrupt is identified by an index (0 to 3). +#[cfg_attr( + multi_core, + doc = r#" + +Please note: Software interrupt 3 is reserved +for inter-processor communication when using +`esp-hal-embassy`."# +)] +#[non_exhaustive] +pub struct SoftwareInterruptControl { + /// Software interrupt 0. + pub software_interrupt0: SoftwareInterrupt<0>, + /// Software interrupt 1. + pub software_interrupt1: SoftwareInterrupt<1>, + /// Software interrupt 2. + pub software_interrupt2: SoftwareInterrupt<2>, + #[cfg(not(all(feature = "__esp_hal_embassy", multi_core)))] + /// Software interrupt 3. Only available when not using `esp-hal-embassy`, + /// or on single-core systems. + pub software_interrupt3: SoftwareInterrupt<3>, +} + +impl SoftwareInterruptControl { + pub fn new(_peripheral: crate::peripherals::SW_INTERRUPT) -> Self { + SoftwareInterruptControl { + software_interrupt0: SoftwareInterrupt {}, + software_interrupt1: SoftwareInterrupt {}, + software_interrupt2: SoftwareInterrupt {}, + #[cfg(not(all(feature = "__esp_hal_embassy", multi_core)))] + software_interrupt3: SoftwareInterrupt {}, + } + } +} diff --git a/esp-hal/src/system.rs b/esp-hal/src/system.rs index 5fbc9029e92..895a980afdc 100755 --- a/esp-hal/src/system.rs +++ b/esp-hal/src/system.rs @@ -6,54 +6,8 @@ //! system-related features and peripherals on ESP chips. It includes //! functionality to control peripheral clocks, manage software interrupts, //! configure chip clocks, and control radio peripherals. -//! -//! ## Software Interrupts -//! -//! The `SoftwareInterruptControl` struct gives access to the available software -//! interrupts. -//! -//! The `SoftwareInterrupt` struct allows raising or resetting software -//! interrupts using the `raise()` and `reset()` methods. -//! -//! ### Examples -//! -//! ```rust, no_run -#![doc = crate::before_snippet!()] -//! let sw_ints = -//! SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); -//! -//! // Take the interrupt you want to use. -//! let mut int0 = sw_ints.software_interrupt0; -//! -//! // Set up the interrupt handler. Do this in a critical section so the global -//! // contains the interrupt object before the interrupt is triggered. -//! critical_section::with(|cs| { -//! int0.set_interrupt_handler(interrupt_handler); -//! SWINT0.borrow_ref_mut(cs).replace(int0); -//! }); -//! # } -//! -//! # use core::cell::RefCell; -//! # use critical_section::Mutex; -//! # use esp_hal::system::{SoftwareInterrupt, SoftwareInterruptControl}; -//! // ... somewhere outside of your main function -//! -//! // Define a shared handle to the software interrupt. -//! static SWINT0: Mutex>>> = -//! Mutex::new(RefCell::new(None)); -//! -//! #[handler] -//! fn interrupt_handler() { -//! // esp_println::println!("SW interrupt0 handled"); -//! -//! // Clear the interrupt request. -//! critical_section::with(|cs| { -//! SWINT0.borrow_ref(cs).as_ref().unwrap().reset(); -//! }); -//! } -//! ``` -use crate::{interrupt::InterruptHandler, peripherals::SYSTEM, InterruptConfigurable}; +use crate::peripherals::SYSTEM; /// Peripherals which can be enabled via `PeripheralClockControl`. /// @@ -168,159 +122,6 @@ pub enum Peripheral { Systimer, } -/// A software interrupt can be triggered by software. -#[non_exhaustive] -pub struct SoftwareInterrupt; - -impl SoftwareInterrupt { - /// Sets the interrupt handler for this software-interrupt - pub fn set_interrupt_handler(&mut self, handler: InterruptHandler) { - let interrupt = match NUM { - 0 => crate::peripherals::Interrupt::FROM_CPU_INTR0, - 1 => crate::peripherals::Interrupt::FROM_CPU_INTR1, - 2 => crate::peripherals::Interrupt::FROM_CPU_INTR2, - 3 => crate::peripherals::Interrupt::FROM_CPU_INTR3, - _ => unreachable!(), - }; - - unsafe { - crate::interrupt::bind_interrupt(interrupt, handler.handler()); - crate::interrupt::enable(interrupt, handler.priority()).unwrap(); - } - } - - /// Trigger this software-interrupt - pub fn raise(&self) { - #[cfg(not(any(esp32c6, esp32h2)))] - let system = unsafe { &*SYSTEM::PTR }; - #[cfg(any(esp32c6, esp32h2))] - let system = unsafe { &*crate::peripherals::INTPRI::PTR }; - - match NUM { - 0 => { - system - .cpu_intr_from_cpu_0() - .write(|w| w.cpu_intr_from_cpu_0().set_bit()); - } - 1 => { - system - .cpu_intr_from_cpu_1() - .write(|w| w.cpu_intr_from_cpu_1().set_bit()); - } - 2 => { - system - .cpu_intr_from_cpu_2() - .write(|w| w.cpu_intr_from_cpu_2().set_bit()); - } - 3 => { - system - .cpu_intr_from_cpu_3() - .write(|w| w.cpu_intr_from_cpu_3().set_bit()); - } - _ => unreachable!(), - } - } - - /// Resets this software-interrupt - pub fn reset(&self) { - #[cfg(not(any(esp32c6, esp32h2)))] - let system = unsafe { &*SYSTEM::PTR }; - #[cfg(any(esp32c6, esp32h2))] - let system = unsafe { &*crate::peripherals::INTPRI::PTR }; - - match NUM { - 0 => { - system - .cpu_intr_from_cpu_0() - .write(|w| w.cpu_intr_from_cpu_0().clear_bit()); - } - 1 => { - system - .cpu_intr_from_cpu_1() - .write(|w| w.cpu_intr_from_cpu_1().clear_bit()); - } - 2 => { - system - .cpu_intr_from_cpu_2() - .write(|w| w.cpu_intr_from_cpu_2().clear_bit()); - } - 3 => { - system - .cpu_intr_from_cpu_3() - .write(|w| w.cpu_intr_from_cpu_3().clear_bit()); - } - _ => unreachable!(), - } - } - - /// Unsafely create an instance of this peripheral out of thin air. - /// - /// # Safety - /// - /// You must ensure that you're only using one instance of this type at a - /// time. - #[inline] - pub unsafe fn steal() -> Self { - Self - } -} - -impl crate::peripheral::Peripheral for SoftwareInterrupt { - type P = SoftwareInterrupt; - - #[inline] - unsafe fn clone_unchecked(&mut self) -> Self::P { - Self::steal() - } -} - -impl crate::private::Sealed for SoftwareInterrupt {} - -impl InterruptConfigurable for SoftwareInterrupt { - fn set_interrupt_handler(&mut self, handler: crate::interrupt::InterruptHandler) { - SoftwareInterrupt::set_interrupt_handler(self, handler); - } -} - -/// This gives access to the available software interrupts. -/// -/// This struct contains several instances of software interrupts that can be -/// used for signaling between different parts of a program or system. Each -/// interrupt is identified by an index (0 to 3). -#[cfg_attr( - multi_core, - doc = r#" - -Please note: Software interrupt 3 is reserved -for inter-processor communication when using -`esp-hal-embassy`."# -)] -#[non_exhaustive] -pub struct SoftwareInterruptControl { - /// Software interrupt 0. - pub software_interrupt0: SoftwareInterrupt<0>, - /// Software interrupt 1. - pub software_interrupt1: SoftwareInterrupt<1>, - /// Software interrupt 2. - pub software_interrupt2: SoftwareInterrupt<2>, - #[cfg(not(all(feature = "__esp_hal_embassy", multi_core)))] - /// Software interrupt 3. Only available when not using `esp-hal-embassy`, - /// or on single-core systems. - pub software_interrupt3: SoftwareInterrupt<3>, -} - -impl SoftwareInterruptControl { - pub fn new(_peripheral: crate::peripherals::SW_INTERRUPT) -> Self { - SoftwareInterruptControl { - software_interrupt0: SoftwareInterrupt {}, - software_interrupt1: SoftwareInterrupt {}, - software_interrupt2: SoftwareInterrupt {}, - #[cfg(not(all(feature = "__esp_hal_embassy", multi_core)))] - software_interrupt3: SoftwareInterrupt {}, - } - } -} - /// Controls the enablement of peripheral clocks. pub(crate) struct PeripheralClockControl; diff --git a/esp-hal/src/timer/systimer.rs b/esp-hal/src/timer/systimer.rs index b740c9877e3..537bdd6d3b3 100644 --- a/esp-hal/src/timer/systimer.rs +++ b/esp-hal/src/timer/systimer.rs @@ -18,8 +18,8 @@ //! //! ### Splitting up the System Timer into three alarms //! -//! Use the [split][SystemTimer::split] method to create three alarms from the System Timer, -//! contained in a [SysTimerAlarms] struct. +//! Use the [split][SystemTimer::split] method to create three alarms from the +//! System Timer, contained in a [SysTimerAlarms] struct. //! //! ```rust, no_run #![doc = crate::before_snippet!()] diff --git a/examples/src/bin/software_interrupts.rs b/examples/src/bin/software_interrupts.rs index 6f7c13e2b26..9ffc150b309 100644 --- a/examples/src/bin/software_interrupts.rs +++ b/examples/src/bin/software_interrupts.rs @@ -15,8 +15,8 @@ use critical_section::Mutex; use esp_backtrace as _; use esp_hal::{ delay::Delay, + interrupt::interrupt::software::{SoftwareInterrupt, SoftwareInterruptControl}, prelude::*, - system::{SoftwareInterrupt, SoftwareInterruptControl}, }; static SWINT0: Mutex>>> = Mutex::new(RefCell::new(None)); diff --git a/hil-test/tests/embassy_interrupt_executor.rs b/hil-test/tests/embassy_interrupt_executor.rs index aa88037a6dc..af76985b219 100644 --- a/hil-test/tests/embassy_interrupt_executor.rs +++ b/hil-test/tests/embassy_interrupt_executor.rs @@ -12,7 +12,7 @@ use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, signal::Signal} use esp_hal::{ clock::CpuClock, interrupt::Priority, - system::{SoftwareInterrupt, SoftwareInterruptControl}, + system::software::{SoftwareInterrupt, SoftwareInterruptControl}, timer::timg::TimerGroup, }; use esp_hal_embassy::InterruptExecutor; diff --git a/hil-test/tests/interrupt.rs b/hil-test/tests/interrupt.rs index 5e7d2d66ae9..9ff1fe9d032 100644 --- a/hil-test/tests/interrupt.rs +++ b/hil-test/tests/interrupt.rs @@ -11,10 +11,12 @@ use core::{arch::asm, cell::RefCell}; use critical_section::Mutex; use esp_hal::{ - interrupt::{self, *}, + interrupt::{ + self, + software::{SoftwareInterrupt, SoftwareInterruptControl}, + }, peripherals::Interrupt, prelude::*, - system::{SoftwareInterrupt, SoftwareInterruptControl}, }; use hil_test as _; From 5cf0602416dac156c4b9a20daddd5b0f39735f2a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Fri, 23 Aug 2024 10:57:44 +0200 Subject: [PATCH 07/19] Re-document what's left in system --- esp-hal/src/system.rs | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/esp-hal/src/system.rs b/esp-hal/src/system.rs index 895a980afdc..4b031e91c17 100755 --- a/esp-hal/src/system.rs +++ b/esp-hal/src/system.rs @@ -2,10 +2,8 @@ //! //! ## Overview //! -//! This `system` driver provides an interface to control and configure various -//! system-related features and peripherals on ESP chips. It includes -//! functionality to control peripheral clocks, manage software interrupts, -//! configure chip clocks, and control radio peripherals. +//! This `system` module defines the available radio peripherals and provides an +//! interface to control and configure radio clocks. use crate::peripherals::SYSTEM; From 6fdd18a46b0d1e30843dbd6fe89c112241d7f080 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Fri, 23 Aug 2024 10:59:32 +0200 Subject: [PATCH 08/19] Update time docs --- esp-hal/src/time.rs | 11 +---------- 1 file changed, 1 insertion(+), 10 deletions(-) diff --git a/esp-hal/src/time.rs b/esp-hal/src/time.rs index 24fe8aff314..82aefad3cd7 100644 --- a/esp-hal/src/time.rs +++ b/esp-hal/src/time.rs @@ -1,17 +1,8 @@ //! # Time //! -//! ## Overview //! The `time` module offers a way to get the system uptime. -//! -//! ## Examples -//! ```rust, no_run -#![doc = crate::before_snippet!()] -//! # use esp_hal::time; -//! let time = time::current_time(); -//! # } -//! ``` -/// Provides time since system start in microseconds precision +/// Provides time since system start in microseconds precision. /// /// The counter won’t measure time in sleep-mode. /// From e01d11cd54645588d74072ae924a04ca80839983 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Mon, 26 Aug 2024 11:24:16 +0200 Subject: [PATCH 09/19] Update sw int docs --- esp-hal/src/interrupt/software.rs | 79 ++++++++------------ esp-hal/src/lib.rs | 4 +- hil-test/tests/embassy_interrupt_executor.rs | 6 +- hil-test/tests/interrupt.rs | 1 + 4 files changed, 40 insertions(+), 50 deletions(-) diff --git a/esp-hal/src/interrupt/software.rs b/esp-hal/src/interrupt/software.rs index e707e1d742a..957bf054375 100644 --- a/esp-hal/src/interrupt/software.rs +++ b/esp-hal/src/interrupt/software.rs @@ -1,10 +1,11 @@ //! # Software Interrupts //! -//! The `SoftwareInterruptControl` struct gives access to the available software -//! interrupts. +//! The [`SoftwareInterruptControl`] struct gives access to the available +//! software interrupts. //! -//! The `SoftwareInterrupt` struct allows raising or resetting software -//! interrupts using the `raise()` and `reset()` methods. +//! The [`SoftwareInterrupt`] struct allows raising or resetting software +//! interrupts using the [`raise()`][SoftwareInterrupt::raise] and +//! [`reset()`][SoftwareInterrupt::reset] methods. //! //! ## Examples //! @@ -44,7 +45,7 @@ //! } //! ``` -use crate::{interrupt::InterruptHandler, peripherals::SYSTEM, InterruptConfigurable}; +use crate::{interrupt::InterruptHandler, InterruptConfigurable}; /// A software interrupt can be triggered by software. #[non_exhaustive] @@ -73,31 +74,23 @@ impl SoftwareInterrupt { if #[cfg(any(esp32c6, esp32h2))] { let system = unsafe { &*crate::peripherals::INTPRI::PTR }; } else { - let system = unsafe { &*SYSTEM::PTR }; + let system = unsafe { &*crate::peripherals::SYSTEM::PTR }; } } match NUM { - 0 => { - system - .cpu_intr_from_cpu_0() - .write(|w| w.cpu_intr_from_cpu_0().set_bit()); - } - 1 => { - system - .cpu_intr_from_cpu_1() - .write(|w| w.cpu_intr_from_cpu_1().set_bit()); - } - 2 => { - system - .cpu_intr_from_cpu_2() - .write(|w| w.cpu_intr_from_cpu_2().set_bit()); - } - 3 => { - system - .cpu_intr_from_cpu_3() - .write(|w| w.cpu_intr_from_cpu_3().set_bit()); - } + 0 => system + .cpu_intr_from_cpu_0() + .write(|w| w.cpu_intr_from_cpu_0().set_bit()), + 1 => system + .cpu_intr_from_cpu_1() + .write(|w| w.cpu_intr_from_cpu_1().set_bit()), + 2 => system + .cpu_intr_from_cpu_2() + .write(|w| w.cpu_intr_from_cpu_2().set_bit()), + 3 => system + .cpu_intr_from_cpu_3() + .write(|w| w.cpu_intr_from_cpu_3().set_bit()), _ => unreachable!(), } } @@ -108,31 +101,23 @@ impl SoftwareInterrupt { if #[cfg(any(esp32c6, esp32h2))] { let system = unsafe { &*crate::peripherals::INTPRI::PTR }; } else { - let system = unsafe { &*SYSTEM::PTR }; + let system = unsafe { &*crate::peripherals::SYSTEM::PTR }; } } match NUM { - 0 => { - system - .cpu_intr_from_cpu_0() - .write(|w| w.cpu_intr_from_cpu_0().clear_bit()); - } - 1 => { - system - .cpu_intr_from_cpu_1() - .write(|w| w.cpu_intr_from_cpu_1().clear_bit()); - } - 2 => { - system - .cpu_intr_from_cpu_2() - .write(|w| w.cpu_intr_from_cpu_2().clear_bit()); - } - 3 => { - system - .cpu_intr_from_cpu_3() - .write(|w| w.cpu_intr_from_cpu_3().clear_bit()); - } + 0 => system + .cpu_intr_from_cpu_0() + .write(|w| w.cpu_intr_from_cpu_0().clear_bit()), + 1 => system + .cpu_intr_from_cpu_1() + .write(|w| w.cpu_intr_from_cpu_1().clear_bit()), + 2 => system + .cpu_intr_from_cpu_2() + .write(|w| w.cpu_intr_from_cpu_2().clear_bit()), + 3 => system + .cpu_intr_from_cpu_3() + .write(|w| w.cpu_intr_from_cpu_3().clear_bit()), _ => unreachable!(), } } diff --git a/esp-hal/src/lib.rs b/esp-hal/src/lib.rs index 10c040d5b26..e86ba740354 100644 --- a/esp-hal/src/lib.rs +++ b/esp-hal/src/lib.rs @@ -102,7 +102,7 @@ //! This means you can pass the pin/peripheral or a mutable reference to the //! pin/peripheral. //! -//! The later can be used to regain access to the pin when the driver gets +//! The latter can be used to regain access to the pin when the driver gets //! dropped. Then it's possible to reuse the pin/peripheral for a different //! purpose. //! @@ -634,6 +634,8 @@ use crate::{ }; /// Initialize the system. +/// +/// This function sets up the CPU clock and returns the peripherals and clocks. pub fn init(clock_config: CpuClock) -> (Peripherals, Clocks<'static>) { let peripherals = Peripherals::take(); let clocks = ClockControl::new(clock_config).freeze(); diff --git a/hil-test/tests/embassy_interrupt_executor.rs b/hil-test/tests/embassy_interrupt_executor.rs index af76985b219..f948689f13b 100644 --- a/hil-test/tests/embassy_interrupt_executor.rs +++ b/hil-test/tests/embassy_interrupt_executor.rs @@ -11,8 +11,10 @@ use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, signal::Signal}; use esp_hal::{ clock::CpuClock, - interrupt::Priority, - system::software::{SoftwareInterrupt, SoftwareInterruptControl}, + interrupt::{ + software::{SoftwareInterrupt, SoftwareInterruptControl}, + Priority, + }, timer::timg::TimerGroup, }; use esp_hal_embassy::InterruptExecutor; diff --git a/hil-test/tests/interrupt.rs b/hil-test/tests/interrupt.rs index 9ff1fe9d032..9b163353891 100644 --- a/hil-test/tests/interrupt.rs +++ b/hil-test/tests/interrupt.rs @@ -14,6 +14,7 @@ use esp_hal::{ interrupt::{ self, software::{SoftwareInterrupt, SoftwareInterruptControl}, + CpuInterrupt, }, peripherals::Interrupt, prelude::*, From b84b5c6b882dbe2aced43689f174265198450b29 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Mon, 26 Aug 2024 11:24:34 +0200 Subject: [PATCH 10/19] Introduce Config --- esp-hal/src/clock/mod.rs | 33 +++++++++---------- esp-hal/src/lib.rs | 16 ++++++--- esp-hal/src/mcpwm/mod.rs | 2 +- esp-hal/src/mcpwm/operator.rs | 2 +- esp-hal/src/prelude.rs | 2 +- esp-hal/src/rom/md5.rs | 4 +-- esp-hal/src/soc/esp32/efuse/mod.rs | 2 +- esp-hal/src/soc/esp32c2/efuse/mod.rs | 2 +- esp-hal/src/soc/esp32c3/efuse/mod.rs | 2 +- esp-hal/src/soc/esp32c6/efuse/mod.rs | 2 +- esp-hal/src/soc/esp32h2/efuse/mod.rs | 2 +- esp-hal/src/soc/esp32s2/efuse/mod.rs | 2 +- esp-hal/src/soc/esp32s3/efuse/mod.rs | 2 +- esp-hal/src/twai/mod.rs | 4 +-- esp-hal/src/uart.rs | 4 +-- examples/src/bin/adc.rs | 2 +- examples/src/bin/adc_cal.rs | 2 +- examples/src/bin/advanced_serial.rs | 2 +- examples/src/bin/blinky.rs | 2 +- examples/src/bin/blinky_erased_pins.rs | 2 +- examples/src/bin/dac.rs | 2 +- examples/src/bin/debug_assist.rs | 2 +- examples/src/bin/dma_extmem2mem.rs | 2 +- examples/src/bin/dma_mem2mem.rs | 2 +- examples/src/bin/embassy_hello_world.rs | 2 +- examples/src/bin/embassy_i2c.rs | 2 +- .../embassy_i2c_bmp180_calibration_data.rs | 2 +- examples/src/bin/embassy_i2s_read.rs | 2 +- examples/src/bin/embassy_i2s_sound.rs | 2 +- examples/src/bin/embassy_multicore.rs | 2 +- .../src/bin/embassy_multicore_interrupt.rs | 2 +- examples/src/bin/embassy_multiprio.rs | 2 +- examples/src/bin/embassy_parl_io_rx.rs | 2 +- examples/src/bin/embassy_parl_io_tx.rs | 2 +- examples/src/bin/embassy_rmt_rx.rs | 2 +- examples/src/bin/embassy_rmt_tx.rs | 2 +- examples/src/bin/embassy_serial.rs | 2 +- examples/src/bin/embassy_spi.rs | 2 +- examples/src/bin/embassy_touch.rs | 2 +- examples/src/bin/embassy_twai.rs | 2 +- examples/src/bin/embassy_usb_serial.rs | 2 +- examples/src/bin/embassy_usb_serial_jtag.rs | 2 +- examples/src/bin/embassy_wait.rs | 2 +- examples/src/bin/etm_blinky_systimer.rs | 2 +- examples/src/bin/etm_gpio.rs | 2 +- examples/src/bin/etm_timer.rs | 2 +- examples/src/bin/gpio_interrupt.rs | 2 +- examples/src/bin/hello_rgb.rs | 2 +- examples/src/bin/hello_world.rs | 2 +- examples/src/bin/hmac.rs | 2 +- .../src/bin/i2c_bmp180_calibration_data.rs | 2 +- examples/src/bin/i2c_display.rs | 2 +- examples/src/bin/i2s_read.rs | 2 +- examples/src/bin/i2s_sound.rs | 2 +- .../src/bin/ieee802154_receive_all_frames.rs | 2 +- examples/src/bin/ieee802154_receive_frame.rs | 2 +- .../bin/ieee802154_send_broadcast_frame.rs | 2 +- examples/src/bin/ieee802154_send_frame.rs | 2 +- examples/src/bin/ieee802154_sniffer.rs | 2 +- examples/src/bin/lcd_cam_ov2640.rs | 2 +- examples/src/bin/lcd_i8080.rs | 2 +- examples/src/bin/ledc.rs | 2 +- examples/src/bin/lp_core_basic.rs | 2 +- examples/src/bin/lp_core_i2c.rs | 2 +- examples/src/bin/lp_core_uart.rs | 2 +- examples/src/bin/mcpwm.rs | 2 +- examples/src/bin/multicore.rs | 2 +- examples/src/bin/parl_io_rx.rs | 2 +- examples/src/bin/parl_io_tx.rs | 2 +- examples/src/bin/pcnt_encoder.rs | 2 +- examples/src/bin/psram_octal.rs | 2 +- examples/src/bin/psram_quad.rs | 2 +- examples/src/bin/qspi_flash.rs | 2 +- examples/src/bin/ram.rs | 2 +- examples/src/bin/rmt_rx.rs | 2 +- examples/src/bin/rmt_tx.rs | 2 +- examples/src/bin/rng.rs | 2 +- examples/src/bin/rtc_time.rs | 2 +- examples/src/bin/rtc_watchdog.rs | 2 +- examples/src/bin/serial_interrupts.rs | 2 +- examples/src/bin/sleep_timer.rs | 2 +- examples/src/bin/sleep_timer_ext0.rs | 2 +- examples/src/bin/sleep_timer_ext1.rs | 2 +- examples/src/bin/sleep_timer_lpio.rs | 2 +- examples/src/bin/sleep_timer_rtcio.rs | 2 +- examples/src/bin/software_interrupts.rs | 2 +- .../spi_halfduplex_read_manufacturer_id.rs | 2 +- examples/src/bin/spi_loopback.rs | 2 +- examples/src/bin/spi_loopback_dma.rs | 2 +- examples/src/bin/spi_slave_dma.rs | 2 +- examples/src/bin/systimer.rs | 2 +- examples/src/bin/timer_interrupt.rs | 2 +- examples/src/bin/touch.rs | 2 +- examples/src/bin/twai.rs | 2 +- examples/src/bin/ulp_riscv_core_basic.rs | 2 +- examples/src/bin/usb_serial.rs | 2 +- examples/src/bin/usb_serial_jtag.rs | 2 +- examples/src/bin/watchdog.rs | 2 +- examples/src/bin/wifi_80211_tx.rs | 6 +++- examples/src/bin/wifi_access_point.rs | 6 +++- .../src/bin/wifi_access_point_with_sta.rs | 6 +++- examples/src/bin/wifi_bench.rs | 6 +++- examples/src/bin/wifi_ble.rs | 6 +++- examples/src/bin/wifi_coex.rs | 6 +++- examples/src/bin/wifi_dhcp.rs | 6 +++- examples/src/bin/wifi_embassy_access_point.rs | 6 +++- .../bin/wifi_embassy_access_point_with_sta.rs | 6 +++- examples/src/bin/wifi_embassy_bench.rs | 6 +++- examples/src/bin/wifi_embassy_ble.rs | 6 +++- examples/src/bin/wifi_embassy_dhcp.rs | 6 +++- examples/src/bin/wifi_embassy_esp_now.rs | 6 +++- .../src/bin/wifi_embassy_esp_now_duplex.rs | 6 +++- examples/src/bin/wifi_esp_now.rs | 6 +++- examples/src/bin/wifi_sniffer.rs | 6 +++- examples/src/bin/wifi_static_ip.rs | 6 +++- hil-test/tests/aes.rs | 6 +++- hil-test/tests/aes_dma.rs | 2 +- hil-test/tests/clock_monitor.rs | 2 +- hil-test/tests/delay.rs | 2 +- hil-test/tests/dma_mem2mem.rs | 2 +- hil-test/tests/ecc.rs | 6 +++- hil-test/tests/embassy_interrupt_executor.rs | 2 +- hil-test/tests/embassy_timers_executors.rs | 2 +- hil-test/tests/get_time.rs | 2 +- hil-test/tests/gpio.rs | 2 +- hil-test/tests/i2s.rs | 2 +- hil-test/tests/i2s_async.rs | 2 +- hil-test/tests/interrupt.rs | 6 +++- hil-test/tests/lcd_cam_i8080.rs | 2 +- hil-test/tests/lcd_cam_i8080_async.rs | 2 +- hil-test/tests/pcnt.rs | 2 +- hil-test/tests/rmt.rs | 2 +- hil-test/tests/rsa.rs | 2 +- hil-test/tests/sha.rs | 7 ++-- hil-test/tests/spi_full_duplex.rs | 2 +- hil-test/tests/spi_full_duplex_dma.rs | 2 +- hil-test/tests/spi_full_duplex_dma_async.rs | 2 +- hil-test/tests/spi_half_duplex_read.rs | 2 +- hil-test/tests/spi_half_duplex_write.rs | 2 +- hil-test/tests/systimer.rs | 2 +- hil-test/tests/twai.rs | 2 +- hil-test/tests/uart.rs | 2 +- hil-test/tests/uart_async.rs | 2 +- hil-test/tests/uart_tx_rx.rs | 2 +- hil-test/tests/uart_tx_rx_async.rs | 2 +- hil-test/tests/usb_serial_jtag.rs | 2 +- 146 files changed, 259 insertions(+), 169 deletions(-) diff --git a/esp-hal/src/clock/mod.rs b/esp-hal/src/clock/mod.rs index 81ea9c2b0e3..ccafb466bd8 100644 --- a/esp-hal/src/clock/mod.rs +++ b/esp-hal/src/clock/mod.rs @@ -48,7 +48,11 @@ //! # } //! # fn main() { //! // Initialize with the highest possible frequency for this chip -//! let system = esp_hal::init(CpuClock::max()); +//! let (peripherals, clocks) = esp_hal::init({ +//! let mut config = Config::default(); +//! config.cpu_clock = CpuClock::max(); +//! config +//! }); //! //! // Initialize with custom clock frequency #![cfg_attr( @@ -59,7 +63,7 @@ #![cfg_attr(esp32h2, doc = "// let system = esp_hal::init(CpuClock::Clock96MHz);")] //! // //! // Initialize with default clock frequency for this chip -//! // let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! // let (peripherals, clocks) = esp_hal::init(Config::default()); //! # } //! ``` @@ -124,13 +128,6 @@ pub enum CpuClock { impl Default for CpuClock { fn default() -> Self { - Self::boot_default() - } -} - -impl CpuClock { - /// Use the default frequency. - pub fn boot_default() -> Self { cfg_if::cfg_if! { if #[cfg(esp32h2)] { Self::Clock96MHz @@ -140,9 +137,11 @@ impl CpuClock { } } } +} +impl CpuClock { /// Use the highest possible frequency for a particular chip. - pub fn max() -> Self { + pub const fn max() -> Self { cfg_if::cfg_if! { if #[cfg(esp32c2)] { Self::Clock120MHz @@ -389,7 +388,7 @@ impl ClockControl { XtalClock::RtcXtalFreq26M }; - if cpu_clock_speed != CpuClock::boot_default() { + if cpu_clock_speed != CpuClock::default() { let pll_freq = match cpu_clock_speed { CpuClock::Clock80MHz => PllClock::Pll320MHz, CpuClock::Clock160MHz => PllClock::Pll320MHz, @@ -429,7 +428,7 @@ impl ClockControl { XTAL_FREQ_MHZ.store(xtal_freq.mhz(), Ordering::Relaxed); let apb_freq; - if cpu_clock_speed != CpuClock::boot_default() { + if cpu_clock_speed != CpuClock::default() { let pll_freq = PllClock::Pll480MHz; if cpu_clock_speed.mhz() <= xtal_freq.mhz() { @@ -464,7 +463,7 @@ impl ClockControl { let xtal_freq = XtalClock::RtcXtalFreq40M; let apb_freq; - if cpu_clock_speed != CpuClock::boot_default() { + if cpu_clock_speed != CpuClock::default() { if cpu_clock_speed.mhz() <= xtal_freq.mhz() { apb_freq = ApbClock::ApbFreqOther(cpu_clock_speed.mhz()); clocks_ll::esp32c3_rtc_update_to_xtal(xtal_freq, 1); @@ -498,7 +497,7 @@ impl ClockControl { let xtal_freq = XtalClock::RtcXtalFreq40M; let apb_freq; - if cpu_clock_speed != CpuClock::boot_default() { + if cpu_clock_speed != CpuClock::default() { if cpu_clock_speed.mhz() <= xtal_freq.mhz() { apb_freq = ApbClock::ApbFreqOther(cpu_clock_speed.mhz()); clocks_ll::esp32c6_rtc_update_to_xtal(xtal_freq, 1); @@ -533,7 +532,7 @@ impl ClockControl { let xtal_freq = XtalClock::RtcXtalFreq32M; let apb_freq; - if cpu_clock_speed != CpuClock::boot_default() { + if cpu_clock_speed != CpuClock::default() { if cpu_clock_speed.mhz() <= xtal_freq.mhz() { apb_freq = ApbClock::ApbFreqOther(cpu_clock_speed.mhz()); clocks_ll::esp32h2_rtc_update_to_xtal(xtal_freq, 1); @@ -567,7 +566,7 @@ impl ClockControl { impl ClockControl { /// Configure the CPU clock speed. pub(crate) fn configure(cpu_clock_speed: CpuClock) -> ClockControl { - if cpu_clock_speed != CpuClock::boot_default() { + if cpu_clock_speed != CpuClock::default() { clocks_ll::set_cpu_clock(cpu_clock_speed); } @@ -585,7 +584,7 @@ impl ClockControl { impl ClockControl { /// Configure the CPU clock speed. pub(crate) fn configure(cpu_clock_speed: CpuClock) -> ClockControl { - if cpu_clock_speed != CpuClock::boot_default() { + if cpu_clock_speed != CpuClock::default() { clocks_ll::set_cpu_clock(cpu_clock_speed); } diff --git a/esp-hal/src/lib.rs b/esp-hal/src/lib.rs index e86ba740354..cf50c207770 100644 --- a/esp-hal/src/lib.rs +++ b/esp-hal/src/lib.rs @@ -73,7 +73,7 @@ //! //! #[entry] //! fn main() -> ! { -//! let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! let (peripherals, clocks) = esp_hal::init(Config::default()); //! //! // Set GPIO0 as an output, and set its state high initially. //! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); @@ -623,7 +623,7 @@ macro_rules! before_snippet { # loop {} # } # fn main() { -# let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +# let (peripherals, clocks) = esp_hal::init(Config::default()); "# }; } @@ -633,12 +633,20 @@ use crate::{ peripherals::Peripherals, }; +/// System configuration. +#[non_exhaustive] +#[derive(Default)] +pub struct Config { + /// The CPU clock configuration. + pub cpu_clock: CpuClock, +} + /// Initialize the system. /// /// This function sets up the CPU clock and returns the peripherals and clocks. -pub fn init(clock_config: CpuClock) -> (Peripherals, Clocks<'static>) { +pub fn init(config: Config) -> (Peripherals, Clocks<'static>) { let peripherals = Peripherals::take(); - let clocks = ClockControl::new(clock_config).freeze(); + let clocks = ClockControl::new(config.cpu_clock).freeze(); (peripherals, clocks) } diff --git a/esp-hal/src/mcpwm/mod.rs b/esp-hal/src/mcpwm/mod.rs index 52d8f17821d..d8c1211ed3a 100644 --- a/esp-hal/src/mcpwm/mod.rs +++ b/esp-hal/src/mcpwm/mod.rs @@ -54,7 +54,7 @@ //! # use esp_hal::mcpwm::{operator::{DeadTimeCfg, PWMStream, PwmPinConfig}, timer::PwmWorkingMode, McPwm, PeripheralClockConfig}; //! # use esp_hal::gpio::Io; //! -//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let pin = io.pins.gpio0; //! diff --git a/esp-hal/src/mcpwm/operator.rs b/esp-hal/src/mcpwm/operator.rs index be980e7910d..2f73324e7ac 100644 --- a/esp-hal/src/mcpwm/operator.rs +++ b/esp-hal/src/mcpwm/operator.rs @@ -486,7 +486,7 @@ impl<'d, Pin: OutputPin, PWM: PwmPeripheral, const OP: u8, const IS_A: bool> /// # use esp_hal::mcpwm::{McPwm, PeripheralClockConfig}; /// # use esp_hal::mcpwm::operator::{DeadTimeCfg, PwmPinConfig, PWMStream}; /// # use esp_hal::gpio::Io; -/// let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +/// let (peripherals, clocks) = esp_hal::init(Config::default()); /// # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); /// // active high complementary using PWMA input /// let bridge_active = DeadTimeCfg::new_ahc(); diff --git a/esp-hal/src/prelude.rs b/esp-hal/src/prelude.rs index 11ad6b9ae56..a6cbed5434d 100644 --- a/esp-hal/src/prelude.rs +++ b/esp-hal/src/prelude.rs @@ -38,4 +38,4 @@ pub use crate::timer::timg::{ pub use crate::timer::Timer as _esp_hal_timer_Timer; #[cfg(any(uart0, uart1, uart2))] pub use crate::uart::Instance as _esp_hal_uart_Instance; -pub use crate::{clock::CpuClock, entry, macros::*, InterruptConfigurable}; +pub use crate::{clock::CpuClock, entry, macros::*, Config, InterruptConfigurable}; diff --git a/esp-hal/src/rom/md5.rs b/esp-hal/src/rom/md5.rs index 85d53017d09..d57adc7155f 100644 --- a/esp-hal/src/rom/md5.rs +++ b/esp-hal/src/rom/md5.rs @@ -35,7 +35,7 @@ //! # use esp_hal::gpio::Io; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut uart0 = Uart::new(peripherals.UART0, &clocks, io.pins.gpio1, io.pins.gpio2).unwrap(); //! # let data = "Dummy"; @@ -52,7 +52,7 @@ //! # use esp_hal::gpio::Io; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut uart0 = Uart::new(peripherals.UART0, &clocks, io.pins.gpio1, io.pins.gpio2).unwrap(); //! # let data0 = "Dummy"; diff --git a/esp-hal/src/soc/esp32/efuse/mod.rs b/esp-hal/src/soc/esp32/efuse/mod.rs index a1cee01c9d8..4b0fe482d2f 100644 --- a/esp-hal/src/soc/esp32/efuse/mod.rs +++ b/esp-hal/src/soc/esp32/efuse/mod.rs @@ -28,7 +28,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); diff --git a/esp-hal/src/soc/esp32c2/efuse/mod.rs b/esp-hal/src/soc/esp32c2/efuse/mod.rs index 1da300d4bab..d43ec0f7561 100644 --- a/esp-hal/src/soc/esp32c2/efuse/mod.rs +++ b/esp-hal/src/soc/esp32c2/efuse/mod.rs @@ -25,7 +25,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); diff --git a/esp-hal/src/soc/esp32c3/efuse/mod.rs b/esp-hal/src/soc/esp32c3/efuse/mod.rs index fe370f833ac..56a4b7e6e50 100644 --- a/esp-hal/src/soc/esp32c3/efuse/mod.rs +++ b/esp-hal/src/soc/esp32c3/efuse/mod.rs @@ -26,7 +26,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); diff --git a/esp-hal/src/soc/esp32c6/efuse/mod.rs b/esp-hal/src/soc/esp32c6/efuse/mod.rs index 7441feecbe3..2cdea9200ab 100644 --- a/esp-hal/src/soc/esp32c6/efuse/mod.rs +++ b/esp-hal/src/soc/esp32c6/efuse/mod.rs @@ -26,7 +26,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); diff --git a/esp-hal/src/soc/esp32h2/efuse/mod.rs b/esp-hal/src/soc/esp32h2/efuse/mod.rs index 1431aebc1ff..51969585d8b 100644 --- a/esp-hal/src/soc/esp32h2/efuse/mod.rs +++ b/esp-hal/src/soc/esp32h2/efuse/mod.rs @@ -26,7 +26,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); diff --git a/esp-hal/src/soc/esp32s2/efuse/mod.rs b/esp-hal/src/soc/esp32s2/efuse/mod.rs index 67ccf16b873..cff5c0db410 100644 --- a/esp-hal/src/soc/esp32s2/efuse/mod.rs +++ b/esp-hal/src/soc/esp32s2/efuse/mod.rs @@ -28,7 +28,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); diff --git a/esp-hal/src/soc/esp32s3/efuse/mod.rs b/esp-hal/src/soc/esp32s3/efuse/mod.rs index c4de385dada..0a4b1c1e49f 100644 --- a/esp-hal/src/soc/esp32s3/efuse/mod.rs +++ b/esp-hal/src/soc/esp32s3/efuse/mod.rs @@ -26,7 +26,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); diff --git a/esp-hal/src/twai/mod.rs b/esp-hal/src/twai/mod.rs index d6e24b5e1ef..75ecb8cd0e8 100644 --- a/esp-hal/src/twai/mod.rs +++ b/esp-hal/src/twai/mod.rs @@ -35,7 +35,7 @@ //! # use esp_hal::gpio::Io; //! # use embedded_can::Frame; //! # use nb::block; -//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! // Use GPIO pins 2 and 3 to connect to the respective pins on the TWAI //! // transceiver. @@ -92,7 +92,7 @@ //! # use esp_hal::gpio::Io; //! # use embedded_can::Frame; //! # use nb::block; -//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! // Use GPIO pins 2 and 3 to connect to the respective pins on the TWAI //! // transceiver. diff --git a/esp-hal/src/uart.rs b/esp-hal/src/uart.rs index 9e048fdfa0b..ee743010e78 100644 --- a/esp-hal/src/uart.rs +++ b/esp-hal/src/uart.rs @@ -58,7 +58,7 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::uart::{config::Config, Uart}; //! # use esp_hal::gpio::Io; -//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut uart1 = Uart::new_with_config( //! # peripherals.UART1, @@ -77,7 +77,7 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::uart::{config::Config, Uart}; //! # use esp_hal::gpio::Io; -//! # let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); +//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut uart1 = Uart::new_with_config( //! # peripherals.UART1, diff --git a/examples/src/bin/adc.rs b/examples/src/bin/adc.rs index b145f219905..ab11bb5e89e 100644 --- a/examples/src/bin/adc.rs +++ b/examples/src/bin/adc.rs @@ -27,7 +27,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/adc_cal.rs b/examples/src/bin/adc_cal.rs index c7ad9f8ae06..d1d667a4c35 100644 --- a/examples/src/bin/adc_cal.rs +++ b/examples/src/bin/adc_cal.rs @@ -23,7 +23,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/advanced_serial.rs b/examples/src/bin/advanced_serial.rs index 43aeebd572d..d41bf15d288 100644 --- a/examples/src/bin/advanced_serial.rs +++ b/examples/src/bin/advanced_serial.rs @@ -19,7 +19,7 @@ use nb::block; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/blinky.rs b/examples/src/bin/blinky.rs index 9776270975a..fc592c4f535 100644 --- a/examples/src/bin/blinky.rs +++ b/examples/src/bin/blinky.rs @@ -17,7 +17,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); // Set GPIO0 as an output, and set its state high initially. let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/blinky_erased_pins.rs b/examples/src/bin/blinky_erased_pins.rs index 1926d42ae5f..435601cbc2c 100644 --- a/examples/src/bin/blinky_erased_pins.rs +++ b/examples/src/bin/blinky_erased_pins.rs @@ -20,7 +20,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/dac.rs b/examples/src/bin/dac.rs index 547a121948f..b379a9b3bd9 100644 --- a/examples/src/bin/dac.rs +++ b/examples/src/bin/dac.rs @@ -23,7 +23,7 @@ use esp_hal::{analog::dac::Dac, delay::Delay, gpio::Io, prelude::*}; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/debug_assist.rs b/examples/src/bin/debug_assist.rs index b39db5d07b7..226fd066725 100644 --- a/examples/src/bin/debug_assist.rs +++ b/examples/src/bin/debug_assist.rs @@ -18,7 +18,7 @@ static DA: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let mut da = DebugAssist::new(peripherals.ASSIST_DEBUG); da.set_interrupt_handler(interrupt_handler); diff --git a/examples/src/bin/dma_extmem2mem.rs b/examples/src/bin/dma_extmem2mem.rs index ac4f53fe9a0..a6ff9a09963 100644 --- a/examples/src/bin/dma_extmem2mem.rs +++ b/examples/src/bin/dma_extmem2mem.rs @@ -62,7 +62,7 @@ fn init_heap(psram: impl esp_hal::peripheral::Peripheral

! { esp_println::logger::init_logger(log::LevelFilter::Info); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); init_heap(peripherals.PSRAM); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/dma_mem2mem.rs b/examples/src/bin/dma_mem2mem.rs index 3a32335800c..5c153ecbfb4 100644 --- a/examples/src/bin/dma_mem2mem.rs +++ b/examples/src/bin/dma_mem2mem.rs @@ -21,7 +21,7 @@ const DATA_SIZE: usize = 1024 * 10; fn main() -> ! { esp_println::logger::init_logger(log::LevelFilter::Info); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/embassy_hello_world.rs b/examples/src/bin/embassy_hello_world.rs index 61d6cd9524c..6e2b4a10079 100644 --- a/examples/src/bin/embassy_hello_world.rs +++ b/examples/src/bin/embassy_hello_world.rs @@ -25,7 +25,7 @@ async fn run() { #[esp_hal_embassy::main] async fn main(spawner: Spawner) { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); esp_println::println!("Init!"); diff --git a/examples/src/bin/embassy_i2c.rs b/examples/src/bin/embassy_i2c.rs index e471357ea83..f5ff82fa146 100644 --- a/examples/src/bin/embassy_i2c.rs +++ b/examples/src/bin/embassy_i2c.rs @@ -24,7 +24,7 @@ use lis3dh_async::{Lis3dh, Range, SlaveAddr}; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs b/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs index ccd27614d79..e30d08eec9e 100644 --- a/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs +++ b/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs @@ -24,7 +24,7 @@ use esp_hal::{gpio::Io, i2c::I2C, prelude::*, timer::timg::TimerGroup}; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_i2s_read.rs b/examples/src/bin/embassy_i2s_read.rs index 7be3b82ce30..ac2f549840e 100644 --- a/examples/src/bin/embassy_i2s_read.rs +++ b/examples/src/bin/embassy_i2s_read.rs @@ -32,7 +32,7 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { println!("Init!"); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_i2s_sound.rs b/examples/src/bin/embassy_i2s_sound.rs index e21cb747d8d..29320016823 100644 --- a/examples/src/bin/embassy_i2s_sound.rs +++ b/examples/src/bin/embassy_i2s_sound.rs @@ -54,7 +54,7 @@ const SINE: [i16; 64] = [ #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { println!("Init!"); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_multicore.rs b/examples/src/bin/embassy_multicore.rs index 2d5797a954b..75262bcb0e5 100644 --- a/examples/src/bin/embassy_multicore.rs +++ b/examples/src/bin/embassy_multicore.rs @@ -51,7 +51,7 @@ async fn control_led( #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/embassy_multicore_interrupt.rs b/examples/src/bin/embassy_multicore_interrupt.rs index 97a2fb210c6..91164fa59b2 100644 --- a/examples/src/bin/embassy_multicore_interrupt.rs +++ b/examples/src/bin/embassy_multicore_interrupt.rs @@ -72,7 +72,7 @@ async fn enable_disable_led(control: &'static Signal ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); diff --git a/examples/src/bin/embassy_multiprio.rs b/examples/src/bin/embassy_multiprio.rs index eb272bbcdff..08c17c9a91e 100644 --- a/examples/src/bin/embassy_multiprio.rs +++ b/examples/src/bin/embassy_multiprio.rs @@ -72,7 +72,7 @@ async fn main(low_prio_spawner: Spawner) { esp_println::logger::init_logger_from_env(); println!("Init!"); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); diff --git a/examples/src/bin/embassy_parl_io_rx.rs b/examples/src/bin/embassy_parl_io_rx.rs index 66177788669..240605be205 100644 --- a/examples/src/bin/embassy_parl_io_rx.rs +++ b/examples/src/bin/embassy_parl_io_rx.rs @@ -26,7 +26,7 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let systimer = SystemTimer::new(peripherals.SYSTIMER).split::(); esp_hal_embassy::init(&clocks, systimer.alarm0); diff --git a/examples/src/bin/embassy_parl_io_tx.rs b/examples/src/bin/embassy_parl_io_tx.rs index 5d56050770d..ba88313e9f7 100644 --- a/examples/src/bin/embassy_parl_io_tx.rs +++ b/examples/src/bin/embassy_parl_io_tx.rs @@ -37,7 +37,7 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let systimer = SystemTimer::new(peripherals.SYSTIMER).split::(); esp_hal_embassy::init(&clocks, systimer.alarm0); diff --git a/examples/src/bin/embassy_rmt_rx.rs b/examples/src/bin/embassy_rmt_rx.rs index b0e958206b7..06c82453713 100644 --- a/examples/src/bin/embassy_rmt_rx.rs +++ b/examples/src/bin/embassy_rmt_rx.rs @@ -39,7 +39,7 @@ async fn signal_task(mut pin: Output<'static, Gpio5>) { #[esp_hal_embassy::main] async fn main(spawner: Spawner) { println!("Init!"); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_rmt_tx.rs b/examples/src/bin/embassy_rmt_tx.rs index 8ab6c589f19..8eed5f6c971 100644 --- a/examples/src/bin/embassy_rmt_tx.rs +++ b/examples/src/bin/embassy_rmt_tx.rs @@ -25,7 +25,7 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { println!("Init!"); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_serial.rs b/examples/src/bin/embassy_serial.rs index 250d716bc69..8b47ce314e8 100644 --- a/examples/src/bin/embassy_serial.rs +++ b/examples/src/bin/embassy_serial.rs @@ -78,7 +78,7 @@ async fn reader( #[esp_hal_embassy::main] async fn main(spawner: Spawner) { esp_println::println!("Init!"); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_spi.rs b/examples/src/bin/embassy_spi.rs index 24a0e4b47cb..ee06bbb7ab3 100644 --- a/examples/src/bin/embassy_spi.rs +++ b/examples/src/bin/embassy_spi.rs @@ -33,7 +33,7 @@ use esp_hal::{ #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_touch.rs b/examples/src/bin/embassy_touch.rs index 524255cd8d4..25e28169a54 100644 --- a/examples/src/bin/embassy_touch.rs +++ b/examples/src/bin/embassy_touch.rs @@ -27,7 +27,7 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_twai.rs b/examples/src/bin/embassy_twai.rs index 53435d2f279..4740af9a861 100644 --- a/examples/src/bin/embassy_twai.rs +++ b/examples/src/bin/embassy_twai.rs @@ -82,7 +82,7 @@ async fn transmitter( #[esp_hal_embassy::main] async fn main(spawner: Spawner) { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_usb_serial.rs b/examples/src/bin/embassy_usb_serial.rs index 47ab396cca9..0e1734b4e0f 100644 --- a/examples/src/bin/embassy_usb_serial.rs +++ b/examples/src/bin/embassy_usb_serial.rs @@ -32,7 +32,7 @@ use esp_hal::{ #[esp_hal_embassy::main] async fn main(_spawner: Spawner) -> () { esp_println::println!("Init!"); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_usb_serial_jtag.rs b/examples/src/bin/embassy_usb_serial_jtag.rs index af4f8e3d89f..5b784c0f90a 100644 --- a/examples/src/bin/embassy_usb_serial_jtag.rs +++ b/examples/src/bin/embassy_usb_serial_jtag.rs @@ -63,7 +63,7 @@ async fn reader( #[esp_hal_embassy::main] async fn main(spawner: Spawner) -> () { esp_println::println!("Init!"); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_wait.rs b/examples/src/bin/embassy_wait.rs index 2db9b2cbd27..f8667a38392 100644 --- a/examples/src/bin/embassy_wait.rs +++ b/examples/src/bin/embassy_wait.rs @@ -19,7 +19,7 @@ use esp_hal::{ #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/etm_blinky_systimer.rs b/examples/src/bin/etm_blinky_systimer.rs index 6e0fcbdff42..97432cbdb8f 100644 --- a/examples/src/bin/etm_blinky_systimer.rs +++ b/examples/src/bin/etm_blinky_systimer.rs @@ -24,7 +24,7 @@ use fugit::ExtU32; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); let syst = SystemTimer::new(peripherals.SYSTIMER); let syst_alarms = syst.split::(); diff --git a/examples/src/bin/etm_gpio.rs b/examples/src/bin/etm_gpio.rs index c11beed9003..b470e6f054c 100644 --- a/examples/src/bin/etm_gpio.rs +++ b/examples/src/bin/etm_gpio.rs @@ -22,7 +22,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let mut led = io.pins.gpio1; diff --git a/examples/src/bin/etm_timer.rs b/examples/src/bin/etm_timer.rs index 2650f223559..07b3ef571f9 100644 --- a/examples/src/bin/etm_timer.rs +++ b/examples/src/bin/etm_timer.rs @@ -28,7 +28,7 @@ static TIMER0: Mutex, esp_hal::Blocking>>>> = #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); let timer0 = timg0.timer0; diff --git a/examples/src/bin/gpio_interrupt.rs b/examples/src/bin/gpio_interrupt.rs index b8efe82a01e..2082353458a 100644 --- a/examples/src/bin/gpio_interrupt.rs +++ b/examples/src/bin/gpio_interrupt.rs @@ -32,7 +32,7 @@ cfg_if::cfg_if! { #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); // Set GPIO2 as an output, and set its state high initially. let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/hello_rgb.rs b/examples/src/bin/hello_rgb.rs index a2095e99d81..fbc9a937032 100644 --- a/examples/src/bin/hello_rgb.rs +++ b/examples/src/bin/hello_rgb.rs @@ -36,7 +36,7 @@ use smart_leds::{ #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/hello_world.rs b/examples/src/bin/hello_world.rs index 0126d62259c..18728385f7b 100644 --- a/examples/src/bin/hello_world.rs +++ b/examples/src/bin/hello_world.rs @@ -19,7 +19,7 @@ use esp_hal::{delay::Delay, gpio::Io, prelude::*, uart::Uart}; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/hmac.rs b/examples/src/bin/hmac.rs index 8c1f16d0529..7c5adf1ffdf 100644 --- a/examples/src/bin/hmac.rs +++ b/examples/src/bin/hmac.rs @@ -73,7 +73,7 @@ type HmacSha256 = HmacSw; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); let mut rng = Rng::new(peripherals.RNG); diff --git a/examples/src/bin/i2c_bmp180_calibration_data.rs b/examples/src/bin/i2c_bmp180_calibration_data.rs index f0995b795f8..cd6fd36ee15 100644 --- a/examples/src/bin/i2c_bmp180_calibration_data.rs +++ b/examples/src/bin/i2c_bmp180_calibration_data.rs @@ -17,7 +17,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/i2c_display.rs b/examples/src/bin/i2c_display.rs index 90e3ed64e22..48caa04f6fc 100644 --- a/examples/src/bin/i2c_display.rs +++ b/examples/src/bin/i2c_display.rs @@ -28,7 +28,7 @@ use ssd1306::{prelude::*, I2CDisplayInterface, Ssd1306}; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let delay = Delay::new(&clocks); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/i2s_read.rs b/examples/src/bin/i2s_read.rs index 21c5c7b4c54..e4b926f2191 100644 --- a/examples/src/bin/i2s_read.rs +++ b/examples/src/bin/i2s_read.rs @@ -28,7 +28,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/i2s_sound.rs b/examples/src/bin/i2s_sound.rs index 4eb64a2737b..4fe2b5894c0 100644 --- a/examples/src/bin/i2s_sound.rs +++ b/examples/src/bin/i2s_sound.rs @@ -49,7 +49,7 @@ const SINE: [i16; 64] = [ #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/ieee802154_receive_all_frames.rs b/examples/src/bin/ieee802154_receive_all_frames.rs index a1b2897f012..583503c69fb 100644 --- a/examples/src/bin/ieee802154_receive_all_frames.rs +++ b/examples/src/bin/ieee802154_receive_all_frames.rs @@ -10,7 +10,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); let mut ieee802154 = Ieee802154::new(peripherals.IEEE802154, &mut peripherals.RADIO_CLK); ieee802154.set_config(Config { diff --git a/examples/src/bin/ieee802154_receive_frame.rs b/examples/src/bin/ieee802154_receive_frame.rs index de4ceccaf95..723153a877b 100644 --- a/examples/src/bin/ieee802154_receive_frame.rs +++ b/examples/src/bin/ieee802154_receive_frame.rs @@ -10,7 +10,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (mut peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (mut peripherals, _clocks) = esp_hal::init(Config::default()); let mut ieee802154 = Ieee802154::new(peripherals.IEEE802154, &mut peripherals.RADIO_CLK); ieee802154.set_config(Config { diff --git a/examples/src/bin/ieee802154_send_broadcast_frame.rs b/examples/src/bin/ieee802154_send_broadcast_frame.rs index 92b7a2c1210..9b04f678391 100644 --- a/examples/src/bin/ieee802154_send_broadcast_frame.rs +++ b/examples/src/bin/ieee802154_send_broadcast_frame.rs @@ -19,7 +19,7 @@ use ieee802154::mac::{ #[entry] fn main() -> ! { - let (mut peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (mut peripherals, clocks) = esp_hal::init(Config::default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/ieee802154_send_frame.rs b/examples/src/bin/ieee802154_send_frame.rs index 78a8b2b9bdc..15297085d15 100644 --- a/examples/src/bin/ieee802154_send_frame.rs +++ b/examples/src/bin/ieee802154_send_frame.rs @@ -19,7 +19,7 @@ use ieee802154::mac::{ #[entry] fn main() -> ! { - let (mut peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (mut peripherals, clocks) = esp_hal::init(Config::default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/ieee802154_sniffer.rs b/examples/src/bin/ieee802154_sniffer.rs index bd5d0d69778..ae1102fdcac 100644 --- a/examples/src/bin/ieee802154_sniffer.rs +++ b/examples/src/bin/ieee802154_sniffer.rs @@ -14,7 +14,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (mut peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (mut peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/lcd_cam_ov2640.rs b/examples/src/bin/lcd_cam_ov2640.rs index 24f5cffbed5..1ff4d9486b0 100644 --- a/examples/src/bin/lcd_cam_ov2640.rs +++ b/examples/src/bin/lcd_cam_ov2640.rs @@ -42,7 +42,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/lcd_i8080.rs b/examples/src/bin/lcd_i8080.rs index 8d60cd76998..19262cc3586 100644 --- a/examples/src/bin/lcd_i8080.rs +++ b/examples/src/bin/lcd_i8080.rs @@ -37,7 +37,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/ledc.rs b/examples/src/bin/ledc.rs index c0649053f00..4b1a2d43702 100644 --- a/examples/src/bin/ledc.rs +++ b/examples/src/bin/ledc.rs @@ -24,7 +24,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let led = io.pins.gpio0; diff --git a/examples/src/bin/lp_core_basic.rs b/examples/src/bin/lp_core_basic.rs index 815bb8ebf8a..a868158cdb8 100644 --- a/examples/src/bin/lp_core_basic.rs +++ b/examples/src/bin/lp_core_basic.rs @@ -23,7 +23,7 @@ use esp_println::{print, println}; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); // configure GPIO 1 as LP output pin let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/lp_core_i2c.rs b/examples/src/bin/lp_core_i2c.rs index e0188b9577e..4f21a5b70b7 100644 --- a/examples/src/bin/lp_core_i2c.rs +++ b/examples/src/bin/lp_core_i2c.rs @@ -25,7 +25,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/lp_core_uart.rs b/examples/src/bin/lp_core_uart.rs index 279cf24ed11..4a8431e2447 100644 --- a/examples/src/bin/lp_core_uart.rs +++ b/examples/src/bin/lp_core_uart.rs @@ -28,7 +28,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/mcpwm.rs b/examples/src/bin/mcpwm.rs index 2cd0c8fe8a7..0e072159983 100644 --- a/examples/src/bin/mcpwm.rs +++ b/examples/src/bin/mcpwm.rs @@ -18,7 +18,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let pin = io.pins.gpio0; diff --git a/examples/src/bin/multicore.rs b/examples/src/bin/multicore.rs index 3ce24dee0dd..aeb57e05075 100644 --- a/examples/src/bin/multicore.rs +++ b/examples/src/bin/multicore.rs @@ -23,7 +23,7 @@ static mut APP_CORE_STACK: Stack<8192> = Stack::new(); #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/parl_io_rx.rs b/examples/src/bin/parl_io_rx.rs index 89996729dc7..ea3f163bcd2 100644 --- a/examples/src/bin/parl_io_rx.rs +++ b/examples/src/bin/parl_io_rx.rs @@ -22,7 +22,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/parl_io_tx.rs b/examples/src/bin/parl_io_tx.rs index ab95783deed..8f0bc12bbdc 100644 --- a/examples/src/bin/parl_io_tx.rs +++ b/examples/src/bin/parl_io_tx.rs @@ -33,7 +33,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/pcnt_encoder.rs b/examples/src/bin/pcnt_encoder.rs index 7a2d9029e3d..eb40c7f7d8e 100644 --- a/examples/src/bin/pcnt_encoder.rs +++ b/examples/src/bin/pcnt_encoder.rs @@ -37,7 +37,7 @@ static VALUE: AtomicI32 = AtomicI32::new(0); #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/psram_octal.rs b/examples/src/bin/psram_octal.rs index b7aa1225863..dad49894939 100644 --- a/examples/src/bin/psram_octal.rs +++ b/examples/src/bin/psram_octal.rs @@ -30,7 +30,7 @@ fn main() -> ! { #[cfg(debug_assertions)] compile_error!("This example MUST be built in release mode!"); - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); psram::init_psram(peripherals.PSRAM); init_psram_heap(); diff --git a/examples/src/bin/psram_quad.rs b/examples/src/bin/psram_quad.rs index 88b03467d20..3037206f091 100644 --- a/examples/src/bin/psram_quad.rs +++ b/examples/src/bin/psram_quad.rs @@ -30,7 +30,7 @@ fn main() -> ! { #[cfg(debug_assertions)] compile_error!("PSRAM example must be built in release mode!"); - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); psram::init_psram(peripherals.PSRAM); init_psram_heap(); diff --git a/examples/src/bin/qspi_flash.rs b/examples/src/bin/qspi_flash.rs index d6e57e036b6..169d7853dc0 100644 --- a/examples/src/bin/qspi_flash.rs +++ b/examples/src/bin/qspi_flash.rs @@ -44,7 +44,7 @@ use esp_println::{print, println}; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/ram.rs b/examples/src/bin/ram.rs index b45b1cd1d45..91af1b6f168 100644 --- a/examples/src/bin/ram.rs +++ b/examples/src/bin/ram.rs @@ -31,7 +31,7 @@ static mut SOME_ZEROED_DATA: [u8; 8] = [0; 8]; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/rmt_rx.rs b/examples/src/bin/rmt_rx.rs index 6c55dc1aa19..3592a39564c 100644 --- a/examples/src/bin/rmt_rx.rs +++ b/examples/src/bin/rmt_rx.rs @@ -24,7 +24,7 @@ const WIDTH: usize = 80; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let mut out = io.pins.gpio5; diff --git a/examples/src/bin/rmt_tx.rs b/examples/src/bin/rmt_tx.rs index 6ae28c27221..d7df0f7d7a5 100644 --- a/examples/src/bin/rmt_tx.rs +++ b/examples/src/bin/rmt_tx.rs @@ -20,7 +20,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/rng.rs b/examples/src/bin/rng.rs index d69920fb336..ac240de253d 100644 --- a/examples/src/bin/rng.rs +++ b/examples/src/bin/rng.rs @@ -11,7 +11,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); let mut rng = Rng::new(peripherals.RNG); // Generate a random word (u32): diff --git a/examples/src/bin/rtc_time.rs b/examples/src/bin/rtc_time.rs index 5d93ec4b196..662531c9a0b 100644 --- a/examples/src/bin/rtc_time.rs +++ b/examples/src/bin/rtc_time.rs @@ -10,7 +10,7 @@ use esp_hal::{delay::Delay, prelude::*, rtc_cntl::Rtc}; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let rtc = Rtc::new(peripherals.LPWR); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/rtc_watchdog.rs b/examples/src/bin/rtc_watchdog.rs index 4beb8991543..badda73d47f 100644 --- a/examples/src/bin/rtc_watchdog.rs +++ b/examples/src/bin/rtc_watchdog.rs @@ -24,7 +24,7 @@ static RWDT: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); let mut rtc = Rtc::new(peripherals.LPWR); rtc.set_interrupt_handler(interrupt_handler); diff --git a/examples/src/bin/serial_interrupts.rs b/examples/src/bin/serial_interrupts.rs index 9d8a48da265..2985b75dd6c 100644 --- a/examples/src/bin/serial_interrupts.rs +++ b/examples/src/bin/serial_interrupts.rs @@ -27,7 +27,7 @@ static SERIAL: Mutex>>> = Mutex::new(RefCel #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/sleep_timer.rs b/examples/src/bin/sleep_timer.rs index 07464fcf6f4..9296fd7df52 100644 --- a/examples/src/bin/sleep_timer.rs +++ b/examples/src/bin/sleep_timer.rs @@ -18,7 +18,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let delay = Delay::new(&clocks); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_ext0.rs b/examples/src/bin/sleep_timer_ext0.rs index f6608cd71d5..bd6576fc83d 100644 --- a/examples/src/bin/sleep_timer_ext0.rs +++ b/examples/src/bin/sleep_timer_ext0.rs @@ -28,7 +28,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_ext1.rs b/examples/src/bin/sleep_timer_ext1.rs index 9c7687f4f52..7aacd563372 100644 --- a/examples/src/bin/sleep_timer_ext1.rs +++ b/examples/src/bin/sleep_timer_ext1.rs @@ -28,7 +28,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_lpio.rs b/examples/src/bin/sleep_timer_lpio.rs index f76a5e0d0ef..cba6153aaa7 100644 --- a/examples/src/bin/sleep_timer_lpio.rs +++ b/examples/src/bin/sleep_timer_lpio.rs @@ -29,7 +29,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_rtcio.rs b/examples/src/bin/sleep_timer_rtcio.rs index ed8bbad6a6a..8588159b700 100644 --- a/examples/src/bin/sleep_timer_rtcio.rs +++ b/examples/src/bin/sleep_timer_rtcio.rs @@ -33,7 +33,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/software_interrupts.rs b/examples/src/bin/software_interrupts.rs index 9ffc150b309..44c655ec9db 100644 --- a/examples/src/bin/software_interrupts.rs +++ b/examples/src/bin/software_interrupts.rs @@ -26,7 +26,7 @@ static SWINT3: Mutex>>> = Mutex::new(RefCell #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let mut sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); diff --git a/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs b/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs index 20a2e9bd81b..3eba959f865 100644 --- a/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs +++ b/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs @@ -42,7 +42,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/spi_loopback.rs b/examples/src/bin/spi_loopback.rs index b0a37b23bfb..aff017521b3 100644 --- a/examples/src/bin/spi_loopback.rs +++ b/examples/src/bin/spi_loopback.rs @@ -29,7 +29,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/examples/src/bin/spi_loopback_dma.rs b/examples/src/bin/spi_loopback_dma.rs index 3b2e7b3579f..3737936cd96 100644 --- a/examples/src/bin/spi_loopback_dma.rs +++ b/examples/src/bin/spi_loopback_dma.rs @@ -34,7 +34,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/examples/src/bin/spi_slave_dma.rs b/examples/src/bin/spi_slave_dma.rs index 42242b96e60..da583f91cd4 100644 --- a/examples/src/bin/spi_slave_dma.rs +++ b/examples/src/bin/spi_slave_dma.rs @@ -45,7 +45,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let slave_sclk = io.pins.gpio0; diff --git a/examples/src/bin/systimer.rs b/examples/src/bin/systimer.rs index 122c96cb088..508ea7e98e6 100644 --- a/examples/src/bin/systimer.rs +++ b/examples/src/bin/systimer.rs @@ -47,7 +47,7 @@ static ALARM2: Mutex< #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let systimer = SystemTimer::new(peripherals.SYSTIMER); println!("SYSTIMER Current value = {}", SystemTimer::now()); diff --git a/examples/src/bin/timer_interrupt.rs b/examples/src/bin/timer_interrupt.rs index 5adec94ab72..1126ba58a4e 100644 --- a/examples/src/bin/timer_interrupt.rs +++ b/examples/src/bin/timer_interrupt.rs @@ -23,7 +23,7 @@ static TIMER0: Mutex, esp_hal::Blocking>>>> = #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); let timer0 = timg0.timer0; diff --git a/examples/src/bin/touch.rs b/examples/src/bin/touch.rs index 6c00245b7e3..88c15097ded 100644 --- a/examples/src/bin/touch.rs +++ b/examples/src/bin/touch.rs @@ -48,7 +48,7 @@ fn interrupt_handler() { #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/twai.rs b/examples/src/bin/twai.rs index a32b69b1f29..380cbf63192 100644 --- a/examples/src/bin/twai.rs +++ b/examples/src/bin/twai.rs @@ -35,7 +35,7 @@ use nb::block; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/ulp_riscv_core_basic.rs b/examples/src/bin/ulp_riscv_core_basic.rs index ac09e536ab6..77e89ae8c23 100644 --- a/examples/src/bin/ulp_riscv_core_basic.rs +++ b/examples/src/bin/ulp_riscv_core_basic.rs @@ -21,7 +21,7 @@ use esp_println::{print, println}; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let pin = LowPowerOutput::new(io.pins.gpio1); diff --git a/examples/src/bin/usb_serial.rs b/examples/src/bin/usb_serial.rs index 3719fbc9508..96d8fad6d15 100644 --- a/examples/src/bin/usb_serial.rs +++ b/examples/src/bin/usb_serial.rs @@ -26,7 +26,7 @@ static mut EP_MEMORY: [u32; 1024] = [0; 1024]; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/usb_serial_jtag.rs b/examples/src/bin/usb_serial_jtag.rs index 06687a13c34..2b81ba5492c 100644 --- a/examples/src/bin/usb_serial_jtag.rs +++ b/examples/src/bin/usb_serial_jtag.rs @@ -23,7 +23,7 @@ static USB_SERIAL: Mutex>>> = #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/watchdog.rs b/examples/src/bin/watchdog.rs index 03b61ecd4b8..78cd2c252c6 100644 --- a/examples/src/bin/watchdog.rs +++ b/examples/src/bin/watchdog.rs @@ -14,7 +14,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/wifi_80211_tx.rs b/examples/src/bin/wifi_80211_tx.rs index 0010e1b4553..b129f288641 100644 --- a/examples/src/bin/wifi_80211_tx.rs +++ b/examples/src/bin/wifi_80211_tx.rs @@ -34,7 +34,11 @@ const MAC_ADDRESS: [u8; 6] = [0x00, 0x80, 0x41, 0x13, 0x37, 0x42]; #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/wifi_access_point.rs b/examples/src/bin/wifi_access_point.rs index 2f56f3792f5..b79f2dcf54b 100644 --- a/examples/src/bin/wifi_access_point.rs +++ b/examples/src/bin/wifi_access_point.rs @@ -34,7 +34,11 @@ use smoltcp::iface::SocketStorage; #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_access_point_with_sta.rs b/examples/src/bin/wifi_access_point_with_sta.rs index 72e1e2a9b8e..69005fd16eb 100644 --- a/examples/src/bin/wifi_access_point_with_sta.rs +++ b/examples/src/bin/wifi_access_point_with_sta.rs @@ -41,7 +41,11 @@ const PASSWORD: &str = env!("PASSWORD"); #[entry] fn main() -> ! { esp_println::logger::init_logger(log::LevelFilter::Info); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_bench.rs b/examples/src/bin/wifi_bench.rs index 429a27ed5c8..b2ebbad932b 100644 --- a/examples/src/bin/wifi_bench.rs +++ b/examples/src/bin/wifi_bench.rs @@ -51,7 +51,11 @@ const UPLOAD_DOWNLOAD_PORT: u16 = 4323; #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let server_address: Ipv4Address = HOST_IP.parse().expect("Invalid HOST_IP address"); diff --git a/examples/src/bin/wifi_ble.rs b/examples/src/bin/wifi_ble.rs index f5f2010841c..13558d6697b 100644 --- a/examples/src/bin/wifi_ble.rs +++ b/examples/src/bin/wifi_ble.rs @@ -36,7 +36,11 @@ use esp_wifi::{ble::controller::BleConnector, initialize, EspWifiInitFor}; #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_coex.rs b/examples/src/bin/wifi_coex.rs index 7087ac24c00..a62eec72c79 100644 --- a/examples/src/bin/wifi_coex.rs +++ b/examples/src/bin/wifi_coex.rs @@ -47,7 +47,11 @@ const PASSWORD: &str = env!("PASSWORD"); #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_dhcp.rs b/examples/src/bin/wifi_dhcp.rs index 74fea7ca852..1819d551048 100644 --- a/examples/src/bin/wifi_dhcp.rs +++ b/examples/src/bin/wifi_dhcp.rs @@ -40,7 +40,11 @@ const PASSWORD: &str = env!("PASSWORD"); #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_access_point.rs b/examples/src/bin/wifi_embassy_access_point.rs index bdfc63a4a42..1208244f0bf 100644 --- a/examples/src/bin/wifi_embassy_access_point.rs +++ b/examples/src/bin/wifi_embassy_access_point.rs @@ -56,7 +56,11 @@ macro_rules! mk_static { #[esp_hal_embassy::main] async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_access_point_with_sta.rs b/examples/src/bin/wifi_embassy_access_point_with_sta.rs index 5cb2a7dd5c1..733a035093f 100644 --- a/examples/src/bin/wifi_embassy_access_point_with_sta.rs +++ b/examples/src/bin/wifi_embassy_access_point_with_sta.rs @@ -70,7 +70,11 @@ macro_rules! mk_static { #[esp_hal_embassy::main] async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_bench.rs b/examples/src/bin/wifi_embassy_bench.rs index 5bf9823020c..2db24497831 100644 --- a/examples/src/bin/wifi_embassy_bench.rs +++ b/examples/src/bin/wifi_embassy_bench.rs @@ -66,7 +66,11 @@ static mut TX_BUFFER: [u8; TX_BUFFER_SIZE] = [0; TX_BUFFER_SIZE]; #[esp_hal_embassy::main] async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let server_address: Ipv4Address = HOST_IP.parse().expect("Invalid HOST_IP address"); diff --git a/examples/src/bin/wifi_embassy_ble.rs b/examples/src/bin/wifi_embassy_ble.rs index d54c99516b9..559cf1ed490 100644 --- a/examples/src/bin/wifi_embassy_ble.rs +++ b/examples/src/bin/wifi_embassy_ble.rs @@ -38,7 +38,11 @@ use esp_wifi::{ble::controller::asynch::BleConnector, initialize, EspWifiInitFor #[esp_hal_embassy::main] async fn main(_spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_dhcp.rs b/examples/src/bin/wifi_embassy_dhcp.rs index 3c371cafdd2..789ac88964a 100644 --- a/examples/src/bin/wifi_embassy_dhcp.rs +++ b/examples/src/bin/wifi_embassy_dhcp.rs @@ -49,7 +49,11 @@ const PASSWORD: &str = env!("PASSWORD"); #[esp_hal_embassy::main] async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_esp_now.rs b/examples/src/bin/wifi_embassy_esp_now.rs index 031b97cd62c..cf23adf050b 100644 --- a/examples/src/bin/wifi_embassy_esp_now.rs +++ b/examples/src/bin/wifi_embassy_esp_now.rs @@ -25,7 +25,11 @@ use esp_wifi::{ #[esp_hal_embassy::main] async fn main(_spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_embassy_esp_now_duplex.rs b/examples/src/bin/wifi_embassy_esp_now_duplex.rs index 7d7cf4b8ae4..027fc3d5db7 100644 --- a/examples/src/bin/wifi_embassy_esp_now_duplex.rs +++ b/examples/src/bin/wifi_embassy_esp_now_duplex.rs @@ -35,7 +35,11 @@ macro_rules! mk_static { #[esp_hal_embassy::main] async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_esp_now.rs b/examples/src/bin/wifi_esp_now.rs index f3bc86beb85..ae3f8b8c12a 100644 --- a/examples/src/bin/wifi_esp_now.rs +++ b/examples/src/bin/wifi_esp_now.rs @@ -21,7 +21,11 @@ use esp_wifi::{ #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/examples/src/bin/wifi_sniffer.rs b/examples/src/bin/wifi_sniffer.rs index 38f005a61fd..f9d81b19e21 100644 --- a/examples/src/bin/wifi_sniffer.rs +++ b/examples/src/bin/wifi_sniffer.rs @@ -33,7 +33,11 @@ static KNOWN_SSIDS: Mutex>> = Mutex::new(RefCell::new(B #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); // Create a heap allocator, with 32kB of space. heap_allocator!(32_168); diff --git a/examples/src/bin/wifi_static_ip.rs b/examples/src/bin/wifi_static_ip.rs index 41b9547ad03..917043e915d 100644 --- a/examples/src/bin/wifi_static_ip.rs +++ b/examples/src/bin/wifi_static_ip.rs @@ -40,7 +40,11 @@ const GATEWAY_IP: &str = env!("GATEWAY_IP"); #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); diff --git a/hil-test/tests/aes.rs b/hil-test/tests/aes.rs index 4b2cc35332a..1bc59f031e7 100644 --- a/hil-test/tests/aes.rs +++ b/hil-test/tests/aes.rs @@ -17,7 +17,11 @@ struct Context<'a> { impl Context<'_> { pub fn init() -> Self { - let (peripherals, _clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, _clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let aes = Aes::new(peripherals.AES); Context { aes } diff --git a/hil-test/tests/aes_dma.rs b/hil-test/tests/aes_dma.rs index 70bc9d5caec..e36cfa3ec37 100644 --- a/hil-test/tests/aes_dma.rs +++ b/hil-test/tests/aes_dma.rs @@ -29,7 +29,7 @@ mod tests { #[init] fn init() -> Peripherals { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); peripherals } diff --git a/hil-test/tests/clock_monitor.rs b/hil-test/tests/clock_monitor.rs index 54004ffa583..f1ecc9de08f 100644 --- a/hil-test/tests/clock_monitor.rs +++ b/hil-test/tests/clock_monitor.rs @@ -14,7 +14,7 @@ struct Context<'a> { impl Context<'_> { pub fn init() -> Self { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let rtc = Rtc::new(peripherals.LPWR); Context { rtc } diff --git a/hil-test/tests/delay.rs b/hil-test/tests/delay.rs index 698ea65f97a..2ce0448d98e 100644 --- a/hil-test/tests/delay.rs +++ b/hil-test/tests/delay.rs @@ -15,7 +15,7 @@ struct Context { impl Context { pub fn init() -> Self { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let delay = Delay::new(&clocks); Context { delay } diff --git a/hil-test/tests/dma_mem2mem.rs b/hil-test/tests/dma_mem2mem.rs index d612711d617..22d41234f73 100644 --- a/hil-test/tests/dma_mem2mem.rs +++ b/hil-test/tests/dma_mem2mem.rs @@ -39,7 +39,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let dma = Dma::new(peripherals.DMA); let channel = dma.channel0.configure(false, DmaPriority::Priority0); diff --git a/hil-test/tests/ecc.rs b/hil-test/tests/ecc.rs index 4f785152189..c1b294cc135 100644 --- a/hil-test/tests/ecc.rs +++ b/hil-test/tests/ecc.rs @@ -56,7 +56,11 @@ mod tests { #[init] fn init() -> Context<'static> { - let (peripherals, _clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, _clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let ecc = Ecc::new(peripherals.ECC); let rng = Rng::new(peripherals.RNG); diff --git a/hil-test/tests/embassy_interrupt_executor.rs b/hil-test/tests/embassy_interrupt_executor.rs index f948689f13b..44182243dca 100644 --- a/hil-test/tests/embassy_interrupt_executor.rs +++ b/hil-test/tests/embassy_interrupt_executor.rs @@ -45,7 +45,7 @@ mod test { #[init] fn init() -> SoftwareInterrupt<1> { - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/hil-test/tests/embassy_timers_executors.rs b/hil-test/tests/embassy_timers_executors.rs index a6b8a9f504c..cce9c3d8ad4 100644 --- a/hil-test/tests/embassy_timers_executors.rs +++ b/hil-test/tests/embassy_timers_executors.rs @@ -128,7 +128,7 @@ mod test { #[init] fn init() -> (Peripherals, Clocks<'static>) { - esp_hal::init(CpuClock::boot_default()) + esp_hal::init(Config::default()) } #[test] diff --git a/hil-test/tests/get_time.rs b/hil-test/tests/get_time.rs index 59b918e4897..aa37d4b02a2 100644 --- a/hil-test/tests/get_time.rs +++ b/hil-test/tests/get_time.rs @@ -35,7 +35,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let delay = Delay::new(&system.clocks); diff --git a/hil-test/tests/gpio.rs b/hil-test/tests/gpio.rs index e6ececfc256..b20709ceca6 100644 --- a/hil-test/tests/gpio.rs +++ b/hil-test/tests/gpio.rs @@ -34,7 +34,7 @@ struct Context<'d> { impl<'d> Context<'d> { pub fn init() -> Self { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); io.set_interrupt_handler(interrupt_handler); diff --git a/hil-test/tests/i2s.rs b/hil-test/tests/i2s.rs index 20918b4b389..97a74e80e05 100644 --- a/hil-test/tests/i2s.rs +++ b/hil-test/tests/i2s.rs @@ -53,7 +53,7 @@ mod tests { #[test] fn test_i2s_loopback() { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let peripherals = peripherals; let clocks = clocks; diff --git a/hil-test/tests/i2s_async.rs b/hil-test/tests/i2s_async.rs index 75a543fc50f..4aedc47e817 100644 --- a/hil-test/tests/i2s_async.rs +++ b/hil-test/tests/i2s_async.rs @@ -85,7 +85,7 @@ mod tests { async fn test_i2s_loopback() { let spawner = embassy_executor::Spawner::for_current_executor().await; - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let peripherals = peripherals; let clocks = clocks; diff --git a/hil-test/tests/interrupt.rs b/hil-test/tests/interrupt.rs index 9b163353891..ca2192116f7 100644 --- a/hil-test/tests/interrupt.rs +++ b/hil-test/tests/interrupt.rs @@ -63,7 +63,11 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, _clocks) = esp_hal::init(CpuClock::max()); + let (peripherals, _clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); cfg_if::cfg_if! { diff --git a/hil-test/tests/lcd_cam_i8080.rs b/hil-test/tests/lcd_cam_i8080.rs index 02281df1e2f..189b667e1a7 100644 --- a/hil-test/tests/lcd_cam_i8080.rs +++ b/hil-test/tests/lcd_cam_i8080.rs @@ -35,7 +35,7 @@ mod tests { #[init] fn init() -> Context<'static> { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let dma = Dma::new(peripherals.DMA); let lcd_cam = LcdCam::new(peripherals.LCD_CAM); let (tx_buffer, tx_descriptors, _, _) = dma_buffers!(DATA_SIZE, 0); diff --git a/hil-test/tests/lcd_cam_i8080_async.rs b/hil-test/tests/lcd_cam_i8080_async.rs index ee8c86168ff..0114857bf94 100644 --- a/hil-test/tests/lcd_cam_i8080_async.rs +++ b/hil-test/tests/lcd_cam_i8080_async.rs @@ -39,7 +39,7 @@ mod tests { #[init] async fn init() -> Context<'static> { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let dma = Dma::new(peripherals.DMA); let lcd_cam = LcdCam::new_async(peripherals.LCD_CAM); diff --git a/hil-test/tests/pcnt.rs b/hil-test/tests/pcnt.rs index 17c70b94a54..8c07f5ca3d4 100644 --- a/hil-test/tests/pcnt.rs +++ b/hil-test/tests/pcnt.rs @@ -32,7 +32,7 @@ mod tests { #[init] fn init() -> Context<'static> { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/rmt.rs b/hil-test/tests/rmt.rs index 5c50f307f96..5948a253214 100644 --- a/hil-test/tests/rmt.rs +++ b/hil-test/tests/rmt.rs @@ -25,7 +25,7 @@ mod tests { #[test] #[timeout(1)] fn rmt_loopback() { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/rsa.rs b/hil-test/tests/rsa.rs index 59deac571ee..2cd431ea4f2 100644 --- a/hil-test/tests/rsa.rs +++ b/hil-test/tests/rsa.rs @@ -57,7 +57,7 @@ mod tests { #[init] fn init() -> Context<'static> { - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); let mut rsa = Rsa::new(peripherals.RSA); nb::block!(rsa.ready()).unwrap(); diff --git a/hil-test/tests/sha.rs b/hil-test/tests/sha.rs index 47888c792f0..327824e931e 100644 --- a/hil-test/tests/sha.rs +++ b/hil-test/tests/sha.rs @@ -166,12 +166,15 @@ mod tests { cfg_if::cfg_if! { if #[cfg(feature = "esp32")] { // FIXME: max speed fails...? - let (peripherals, _clocks) = esp_hal::init(CpuClock::boot_default()); + let config = Config::default(); } else { - let (peripherals, _clocks) = esp_hal::init(CpuClock::max()); + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); } } + let (peripherals, _clocks) = esp_hal::init(config); + Rng::new(peripherals.RNG) } diff --git a/hil-test/tests/spi_full_duplex.rs b/hil-test/tests/spi_full_duplex.rs index 9865db9a017..fa14ea2b926 100644 --- a/hil-test/tests/spi_full_duplex.rs +++ b/hil-test/tests/spi_full_duplex.rs @@ -34,7 +34,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/spi_full_duplex_dma.rs b/hil-test/tests/spi_full_duplex_dma.rs index 28e0737ee5d..5c9ed59aa97 100644 --- a/hil-test/tests/spi_full_duplex_dma.rs +++ b/hil-test/tests/spi_full_duplex_dma.rs @@ -55,7 +55,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/spi_full_duplex_dma_async.rs b/hil-test/tests/spi_full_duplex_dma_async.rs index e4f0b485145..61b0976e03c 100644 --- a/hil-test/tests/spi_full_duplex_dma_async.rs +++ b/hil-test/tests/spi_full_duplex_dma_async.rs @@ -72,7 +72,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let pcnt = Pcnt::new(peripherals.PCNT); diff --git a/hil-test/tests/spi_half_duplex_read.rs b/hil-test/tests/spi_half_duplex_read.rs index c4bfb75c097..6048c1bccf1 100644 --- a/hil-test/tests/spi_half_duplex_read.rs +++ b/hil-test/tests/spi_half_duplex_read.rs @@ -56,7 +56,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/spi_half_duplex_write.rs b/hil-test/tests/spi_half_duplex_write.rs index 137b0fd0a39..36bafdc1f9f 100644 --- a/hil-test/tests/spi_half_duplex_write.rs +++ b/hil-test/tests/spi_half_duplex_write.rs @@ -65,7 +65,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/systimer.rs b/hil-test/tests/systimer.rs index c419e5503ef..6dd3b95d1c0 100644 --- a/hil-test/tests/systimer.rs +++ b/hil-test/tests/systimer.rs @@ -104,7 +104,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let systimer = SystemTimer::new(peripherals.SYSTIMER); static UNIT0: StaticCell> = StaticCell::new(); diff --git a/hil-test/tests/twai.rs b/hil-test/tests/twai.rs index 40f9844b96f..79b1aa9ac11 100644 --- a/hil-test/tests/twai.rs +++ b/hil-test/tests/twai.rs @@ -35,7 +35,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/uart.rs b/hil-test/tests/uart.rs index 51398f2d10f..ce54367bda8 100644 --- a/hil-test/tests/uart.rs +++ b/hil-test/tests/uart.rs @@ -37,7 +37,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/uart_async.rs b/hil-test/tests/uart_async.rs index a674d6ee3c0..e7fd7f12073 100644 --- a/hil-test/tests/uart_async.rs +++ b/hil-test/tests/uart_async.rs @@ -28,7 +28,7 @@ mod tests { #[init] async fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/uart_tx_rx.rs b/hil-test/tests/uart_tx_rx.rs index b5cc88d5560..ff0c599d173 100644 --- a/hil-test/tests/uart_tx_rx.rs +++ b/hil-test/tests/uart_tx_rx.rs @@ -35,7 +35,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/uart_tx_rx_async.rs b/hil-test/tests/uart_tx_rx_async.rs index 5c6ba5b6f84..c92fa8090ef 100644 --- a/hil-test/tests/uart_tx_rx_async.rs +++ b/hil-test/tests/uart_tx_rx_async.rs @@ -35,7 +35,7 @@ mod tests { #[init] async fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/usb_serial_jtag.rs b/hil-test/tests/usb_serial_jtag.rs index 2b51317dbbb..854e65e4cb0 100644 --- a/hil-test/tests/usb_serial_jtag.rs +++ b/hil-test/tests/usb_serial_jtag.rs @@ -13,7 +13,7 @@ mod tests { #[test] fn creating_peripheral_does_not_break_debug_connection() { - let (peripherals, clocks) = esp_hal::init(CpuClock::boot_default()); + let (peripherals, clocks) = esp_hal::init(Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); From d0fbcd16ac19ddf84b68eaff04f79b5241f473b1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Mon, 26 Aug 2024 11:24:50 +0200 Subject: [PATCH 11/19] Fix tests --- esp-hal/src/lcd_cam/lcd/i8080.rs | 4 ++-- esp-hal/src/uart.rs | 14 +++++++------- examples/src/bin/debug_assist.rs | 2 +- hil-test/tests/embassy_interrupt_executor.rs | 1 + hil-test/tests/embassy_timers_executors.rs | 6 +++--- hil-test/tests/get_time.rs | 12 ++++-------- hil-test/tests/interrupt.rs | 1 + 7 files changed, 19 insertions(+), 21 deletions(-) diff --git a/esp-hal/src/lcd_cam/lcd/i8080.rs b/esp-hal/src/lcd_cam/lcd/i8080.rs index 27af36a8578..694d73b723c 100644 --- a/esp-hal/src/lcd_cam/lcd/i8080.rs +++ b/esp-hal/src/lcd_cam/lcd/i8080.rs @@ -16,7 +16,7 @@ //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::gpio::Io; -//! # use esp_hal::lcd_cam::{LcdCam, lcd::i8080::{Config, I8080, TxEightBits}}; +//! # use esp_hal::lcd_cam::{LcdCam, lcd::i8080::{self, I8080, TxEightBits}}; //! # use esp_hal::dma_buffers; //! # use esp_hal::dma::{Dma, DmaPriority}; //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); @@ -49,7 +49,7 @@ //! tx_descriptors, //! tx_pins, //! 20.MHz(), -//! Config::default(), +//! i8080::Config::default(), //! &clocks, //! ) //! .with_ctrl_pins(io.pins.gpio0, io.pins.gpio47); diff --git a/esp-hal/src/uart.rs b/esp-hal/src/uart.rs index ee743010e78..c1b782135c0 100644 --- a/esp-hal/src/uart.rs +++ b/esp-hal/src/uart.rs @@ -22,7 +22,7 @@ //! //! ```rust, no_run #![doc = crate::before_snippet!()] -//! # use esp_hal::uart::{config::Config, Uart}; +//! # use esp_hal::uart::Uart; //! use esp_hal::gpio::Io; //! //! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); @@ -56,13 +56,13 @@ //! ### Sending and Receiving Data //! ```rust, no_run #![doc = crate::before_snippet!()] -//! # use esp_hal::uart::{config::Config, Uart}; +//! # use esp_hal::uart::{self, Uart}; //! # use esp_hal::gpio::Io; //! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut uart1 = Uart::new_with_config( //! # peripherals.UART1, -//! # Config::default(), +//! # uart::config::Config::default(), //! # &clocks, //! # io.pins.gpio1, //! # io.pins.gpio2, @@ -75,13 +75,13 @@ //! ### Splitting the UART into TX and RX Components //! ```rust, no_run #![doc = crate::before_snippet!()] -//! # use esp_hal::uart::{config::Config, Uart}; +//! # use esp_hal::uart::{self, Uart}; //! # use esp_hal::gpio::Io; //! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut uart1 = Uart::new_with_config( //! # peripherals.UART1, -//! # Config::default(), +//! # uart::config::Config::default(), //! # &clocks, //! # io.pins.gpio1, //! # io.pins.gpio2, @@ -98,7 +98,7 @@ //! ### Inverting TX and RX Pins //! ```rust, no_run #![doc = crate::before_snippet!()] -//! # use esp_hal::uart::{config::Config, Uart}; +//! # use esp_hal::uart::Uart; //! use esp_hal::gpio::{AnyPin, Io}; //! //! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); @@ -117,7 +117,7 @@ //! ### Constructing TX and RX Components //! ```rust, no_run #![doc = crate::before_snippet!()] -//! # use esp_hal::uart::{config::Config, UartTx, UartRx}; +//! # use esp_hal::uart::{UartTx, UartRx}; //! use esp_hal::gpio::{AnyPin, Io}; //! //! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/debug_assist.rs b/examples/src/bin/debug_assist.rs index 226fd066725..1599a77f67d 100644 --- a/examples/src/bin/debug_assist.rs +++ b/examples/src/bin/debug_assist.rs @@ -18,7 +18,7 @@ static DA: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); let mut da = DebugAssist::new(peripherals.ASSIST_DEBUG); da.set_interrupt_handler(interrupt_handler); diff --git a/hil-test/tests/embassy_interrupt_executor.rs b/hil-test/tests/embassy_interrupt_executor.rs index 44182243dca..078d339b451 100644 --- a/hil-test/tests/embassy_interrupt_executor.rs +++ b/hil-test/tests/embassy_interrupt_executor.rs @@ -15,6 +15,7 @@ use esp_hal::{ software::{SoftwareInterrupt, SoftwareInterruptControl}, Priority, }, + prelude::*, timer::timg::TimerGroup, }; use esp_hal_embassy::InterruptExecutor; diff --git a/hil-test/tests/embassy_timers_executors.rs b/hil-test/tests/embassy_timers_executors.rs index cce9c3d8ad4..589a52a174e 100644 --- a/hil-test/tests/embassy_timers_executors.rs +++ b/hil-test/tests/embassy_timers_executors.rs @@ -10,9 +10,9 @@ use embassy_time::{Duration, Ticker, Timer}; use esp_hal::{ clock::Clocks, + interrupt::software::SoftwareInterruptControl, peripherals::Peripherals, prelude::*, - system::SoftwareInterruptControl, timer::{timg::TimerGroup, ErasedTimer, OneShotTimer, PeriodicTimer}, }; #[cfg(not(feature = "esp32"))] @@ -159,7 +159,7 @@ mod test { #[test] #[timeout(3)] #[cfg(not(feature = "esp32"))] - fn test_periodic_systimer((peripherals, clocks): (Peripherals, Clocks<'static>)) { + fn test_periodic_systimer((peripherals, _clocks): (Peripherals, Clocks<'static>)) { let systimer = SystemTimer::new(peripherals.SYSTIMER).split::(); run_test_periodic_timer(systimer.alarm0); @@ -178,7 +178,7 @@ mod test { #[test] #[timeout(3)] #[cfg(not(feature = "esp32"))] - fn test_periodic_oneshot_systimer((mut peripherals, clocks): (Peripherals, Clocks<'static>)) { + fn test_periodic_oneshot_systimer((mut peripherals, _clocks): (Peripherals, Clocks<'static>)) { let mut systimer = SystemTimer::new(&mut peripherals.SYSTIMER); let unit = FrozenUnit::new(&mut systimer.unit0); let mut alarm: Alarm<'_, Periodic, _, _, _> = Alarm::new(systimer.comparator0, &unit); diff --git a/hil-test/tests/get_time.rs b/hil-test/tests/get_time.rs index aa37d4b02a2..ed71ea17c0a 100644 --- a/hil-test/tests/get_time.rs +++ b/hil-test/tests/get_time.rs @@ -7,7 +7,7 @@ #[cfg(esp32)] use esp_hal::clock::Clocks; -use esp_hal::{delay::Delay, prelude::*, system::SystemControl}; +use esp_hal::{delay::Delay, prelude::*}; use hil_test as _; struct Context { @@ -16,10 +16,6 @@ struct Context { clocks: Clocks<'static>, } -impl Context { - pub fn init() -> Self {} -} - fn time_moves_forward_during(ctx: Context, f: F) { let t1 = esp_hal::time::current_time(); f(ctx); @@ -35,14 +31,14 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (_peripherals, clocks) = esp_hal::init(Config::default()); - let delay = Delay::new(&system.clocks); + let delay = Delay::new(&clocks); Context { delay, #[cfg(esp32)] - clocks: system.clocks, + clocks, } } diff --git a/hil-test/tests/interrupt.rs b/hil-test/tests/interrupt.rs index ca2192116f7..ea0173d9492 100644 --- a/hil-test/tests/interrupt.rs +++ b/hil-test/tests/interrupt.rs @@ -15,6 +15,7 @@ use esp_hal::{ self, software::{SoftwareInterrupt, SoftwareInterruptControl}, CpuInterrupt, + Priority, }, peripherals::Interrupt, prelude::*, From 3b7ed969c2037fe25ef64d25768f81b9acfb4c98 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Mon, 26 Aug 2024 14:33:04 +0200 Subject: [PATCH 12/19] Remove redundant inits --- esp-hal/src/mcpwm/mod.rs | 1 - esp-hal/src/rom/md5.rs | 2 -- esp-hal/src/soc/esp32/efuse/mod.rs | 1 - esp-hal/src/soc/esp32c2/efuse/mod.rs | 1 - esp-hal/src/soc/esp32c3/efuse/mod.rs | 1 - esp-hal/src/soc/esp32c6/efuse/mod.rs | 1 - esp-hal/src/soc/esp32h2/efuse/mod.rs | 1 - esp-hal/src/soc/esp32s2/efuse/mod.rs | 1 - esp-hal/src/soc/esp32s3/efuse/mod.rs | 1 - esp-hal/src/twai/mod.rs | 2 -- esp-hal/src/uart.rs | 2 -- 11 files changed, 14 deletions(-) diff --git a/esp-hal/src/mcpwm/mod.rs b/esp-hal/src/mcpwm/mod.rs index d8c1211ed3a..0d1b1cfcd16 100644 --- a/esp-hal/src/mcpwm/mod.rs +++ b/esp-hal/src/mcpwm/mod.rs @@ -54,7 +54,6 @@ //! # use esp_hal::mcpwm::{operator::{DeadTimeCfg, PWMStream, PwmPinConfig}, timer::PwmWorkingMode, McPwm, PeripheralClockConfig}; //! # use esp_hal::gpio::Io; //! -//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let pin = io.pins.gpio0; //! diff --git a/esp-hal/src/rom/md5.rs b/esp-hal/src/rom/md5.rs index d57adc7155f..43b5b7e7e72 100644 --- a/esp-hal/src/rom/md5.rs +++ b/esp-hal/src/rom/md5.rs @@ -35,7 +35,6 @@ //! # use esp_hal::gpio::Io; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut uart0 = Uart::new(peripherals.UART0, &clocks, io.pins.gpio1, io.pins.gpio2).unwrap(); //! # let data = "Dummy"; @@ -52,7 +51,6 @@ //! # use esp_hal::gpio::Io; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut uart0 = Uart::new(peripherals.UART0, &clocks, io.pins.gpio1, io.pins.gpio2).unwrap(); //! # let data0 = "Dummy"; diff --git a/esp-hal/src/soc/esp32/efuse/mod.rs b/esp-hal/src/soc/esp32/efuse/mod.rs index 4b0fe482d2f..63eff59fb7c 100644 --- a/esp-hal/src/soc/esp32/efuse/mod.rs +++ b/esp-hal/src/soc/esp32/efuse/mod.rs @@ -28,7 +28,6 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); diff --git a/esp-hal/src/soc/esp32c2/efuse/mod.rs b/esp-hal/src/soc/esp32c2/efuse/mod.rs index d43ec0f7561..93db7e33dca 100644 --- a/esp-hal/src/soc/esp32c2/efuse/mod.rs +++ b/esp-hal/src/soc/esp32c2/efuse/mod.rs @@ -25,7 +25,6 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); diff --git a/esp-hal/src/soc/esp32c3/efuse/mod.rs b/esp-hal/src/soc/esp32c3/efuse/mod.rs index 56a4b7e6e50..08d81adf092 100644 --- a/esp-hal/src/soc/esp32c3/efuse/mod.rs +++ b/esp-hal/src/soc/esp32c3/efuse/mod.rs @@ -26,7 +26,6 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); diff --git a/esp-hal/src/soc/esp32c6/efuse/mod.rs b/esp-hal/src/soc/esp32c6/efuse/mod.rs index 2cdea9200ab..a49f21870c1 100644 --- a/esp-hal/src/soc/esp32c6/efuse/mod.rs +++ b/esp-hal/src/soc/esp32c6/efuse/mod.rs @@ -26,7 +26,6 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); diff --git a/esp-hal/src/soc/esp32h2/efuse/mod.rs b/esp-hal/src/soc/esp32h2/efuse/mod.rs index 51969585d8b..fbf928a8dec 100644 --- a/esp-hal/src/soc/esp32h2/efuse/mod.rs +++ b/esp-hal/src/soc/esp32h2/efuse/mod.rs @@ -26,7 +26,6 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); diff --git a/esp-hal/src/soc/esp32s2/efuse/mod.rs b/esp-hal/src/soc/esp32s2/efuse/mod.rs index cff5c0db410..bebbf7a1976 100644 --- a/esp-hal/src/soc/esp32s2/efuse/mod.rs +++ b/esp-hal/src/soc/esp32s2/efuse/mod.rs @@ -28,7 +28,6 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); diff --git a/esp-hal/src/soc/esp32s3/efuse/mod.rs b/esp-hal/src/soc/esp32s3/efuse/mod.rs index 0a4b1c1e49f..79445ae675d 100644 --- a/esp-hal/src/soc/esp32s3/efuse/mod.rs +++ b/esp-hal/src/soc/esp32s3/efuse/mod.rs @@ -26,7 +26,6 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut serial_tx = Uart::new(peripherals.UART0, &clocks, io.pins.gpio4, io.pins.gpio5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); diff --git a/esp-hal/src/twai/mod.rs b/esp-hal/src/twai/mod.rs index 75ecb8cd0e8..562b1b9b851 100644 --- a/esp-hal/src/twai/mod.rs +++ b/esp-hal/src/twai/mod.rs @@ -35,7 +35,6 @@ //! # use esp_hal::gpio::Io; //! # use embedded_can::Frame; //! # use nb::block; -//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! // Use GPIO pins 2 and 3 to connect to the respective pins on the TWAI //! // transceiver. @@ -92,7 +91,6 @@ //! # use esp_hal::gpio::Io; //! # use embedded_can::Frame; //! # use nb::block; -//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! // Use GPIO pins 2 and 3 to connect to the respective pins on the TWAI //! // transceiver. diff --git a/esp-hal/src/uart.rs b/esp-hal/src/uart.rs index c1b782135c0..c76756112ed 100644 --- a/esp-hal/src/uart.rs +++ b/esp-hal/src/uart.rs @@ -58,7 +58,6 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::uart::{self, Uart}; //! # use esp_hal::gpio::Io; -//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut uart1 = Uart::new_with_config( //! # peripherals.UART1, @@ -77,7 +76,6 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::uart::{self, Uart}; //! # use esp_hal::gpio::Io; -//! # let (peripherals, clocks) = esp_hal::init(Config::default()); //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut uart1 = Uart::new_with_config( //! # peripherals.UART1, From ef160c722e0a1a1242a1b7ff4b8d478275ff7687 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Tue, 27 Aug 2024 20:26:56 +0200 Subject: [PATCH 13/19] Doc --- esp-hal/src/clock/mod.rs | 10 +++++++--- esp-hal/src/interrupt/software.rs | 1 + 2 files changed, 8 insertions(+), 3 deletions(-) diff --git a/esp-hal/src/clock/mod.rs b/esp-hal/src/clock/mod.rs index ccafb466bd8..100d95454dd 100644 --- a/esp-hal/src/clock/mod.rs +++ b/esp-hal/src/clock/mod.rs @@ -55,12 +55,16 @@ //! }); //! //! // Initialize with custom clock frequency +//! // let (peripherals, clocks) = esp_hal::init({ +//! // let mut config = Config::default(); #![cfg_attr( not(any(esp32c2, esp32h2)), - doc = "// let system = esp_hal::init(CpuClock::Clock160MHz);" + doc = "// config.cpu_clock = CpuClock::Clock160MHz;" )] -#![cfg_attr(esp32c2, doc = "// let system = esp_hal::init(CpuClock::Clock120MHz);")] -#![cfg_attr(esp32h2, doc = "// let system = esp_hal::init(CpuClock::Clock96MHz);")] +#![cfg_attr(esp32c2, doc = "// config.cpu_clock = CpuClock::Clock120MHz;")] +#![cfg_attr(esp32h2, doc = "// config.cpu_clock = CpuClock::Clock96MHz;")] +//! // config +//! // }); //! // //! // Initialize with default clock frequency for this chip //! // let (peripherals, clocks) = esp_hal::init(Config::default()); diff --git a/esp-hal/src/interrupt/software.rs b/esp-hal/src/interrupt/software.rs index 957bf054375..67aab7dcb1d 100644 --- a/esp-hal/src/interrupt/software.rs +++ b/esp-hal/src/interrupt/software.rs @@ -179,6 +179,7 @@ pub struct SoftwareInterruptControl { } impl SoftwareInterruptControl { + /// Create a new instance of the software interrupt control. pub fn new(_peripheral: crate::peripherals::SW_INTERRUPT) -> Self { SoftwareInterruptControl { software_interrupt0: SoftwareInterrupt {}, From 435da71d40d309b79588d1dec4ad998e99f49e1d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Tue, 27 Aug 2024 20:37:04 +0200 Subject: [PATCH 14/19] Clean up examples&tests --- examples/src/bin/embassy_multicore.rs | 1 + .../src/bin/embassy_multicore_interrupt.rs | 3 +-- examples/src/bin/embassy_multiprio.rs | 4 ++-- examples/src/bin/embassy_serial.rs | 5 +++-- examples/src/bin/embassy_touch.rs | 1 + examples/src/bin/embassy_twai.rs | 1 + examples/src/bin/embassy_usb_serial.rs | 5 +++-- examples/src/bin/embassy_usb_serial_jtag.rs | 1 + examples/src/bin/embassy_wait.rs | 13 +++++++++---- .../src/bin/ieee802154_receive_all_frames.rs | 8 ++++---- examples/src/bin/ieee802154_receive_frame.rs | 6 +++--- .../src/bin/ieee802154_send_broadcast_frame.rs | 6 +++--- examples/src/bin/ieee802154_send_frame.rs | 6 +++--- examples/src/bin/ieee802154_sniffer.rs | 6 +++--- examples/src/bin/lcd_i8080.rs | 4 ++-- examples/src/bin/lp_core_uart.rs | 4 ++-- examples/src/bin/psram_quad.rs | 2 +- examples/src/bin/serial_interrupts.rs | 4 ++-- examples/src/bin/sleep_timer.rs | 1 + examples/src/bin/sleep_timer_ext0.rs | 1 + examples/src/bin/sleep_timer_ext1.rs | 1 + examples/src/bin/sleep_timer_lpio.rs | 1 + examples/src/bin/sleep_timer_rtcio.rs | 1 + examples/src/bin/software_interrupts.rs | 18 +++++++++--------- examples/src/bin/spi_loopback_dma.rs | 3 --- examples/src/bin/wifi_ble.rs | 1 - examples/src/bin/wifi_embassy_access_point.rs | 5 ++--- .../bin/wifi_embassy_access_point_with_sta.rs | 13 +++---------- examples/src/bin/wifi_embassy_bench.rs | 6 +++--- examples/src/bin/wifi_embassy_ble.rs | 2 +- examples/src/bin/wifi_embassy_dhcp.rs | 6 +++--- examples/src/bin/wifi_embassy_esp_now.rs | 2 +- .../src/bin/wifi_embassy_esp_now_duplex.rs | 2 +- hil-test/tests/aes_dma.rs | 2 +- hil-test/tests/clock_monitor.rs | 14 ++++---------- hil-test/tests/dma_mem2mem.rs | 2 +- hil-test/tests/embassy_interrupt_executor.rs | 1 - hil-test/tests/sha.rs | 4 ++-- hil-test/tests/spi_full_duplex_dma.rs | 5 ++--- hil-test/tests/spi_full_duplex_dma_async.rs | 4 +--- hil-test/tests/spi_full_duplex_dma_pcnt.rs | 8 ++------ hil-test/tests/spi_half_duplex_read.rs | 4 +--- hil-test/tests/spi_half_duplex_write.rs | 4 +--- 43 files changed, 88 insertions(+), 103 deletions(-) diff --git a/examples/src/bin/embassy_multicore.rs b/examples/src/bin/embassy_multicore.rs index 75262bcb0e5..578a4907f25 100644 --- a/examples/src/bin/embassy_multicore.rs +++ b/examples/src/bin/embassy_multicore.rs @@ -22,6 +22,7 @@ use esp_hal::{ cpu_control::{CpuControl, Stack}, get_core, gpio::{AnyOutput, Io, Level}, + prelude::*, timer::{timg::TimerGroup, ErasedTimer}, }; use esp_hal_embassy::Executor; diff --git a/examples/src/bin/embassy_multicore_interrupt.rs b/examples/src/bin/embassy_multicore_interrupt.rs index 91164fa59b2..82ae89188a0 100644 --- a/examples/src/bin/embassy_multicore_interrupt.rs +++ b/examples/src/bin/embassy_multicore_interrupt.rs @@ -21,9 +21,8 @@ use esp_hal::{ cpu_control::{CpuControl, Stack}, get_core, gpio::{AnyOutput, Io, Level}, - interrupt::Priority, + interrupt::{software::SoftwareInterruptControl, Priority}, prelude::*, - system::SoftwareInterruptControl, timer::{timg::TimerGroup, ErasedTimer}, }; use esp_hal_embassy::InterruptExecutor; diff --git a/examples/src/bin/embassy_multiprio.rs b/examples/src/bin/embassy_multiprio.rs index 08c17c9a91e..56ddc0e7ca7 100644 --- a/examples/src/bin/embassy_multiprio.rs +++ b/examples/src/bin/embassy_multiprio.rs @@ -24,8 +24,8 @@ use embassy_executor::Spawner; use embassy_time::{Duration, Instant, Ticker, Timer}; use esp_backtrace as _; use esp_hal::{ - interrupt::Priority, - system::SoftwareInterruptControl, + interrupt::{software::SoftwareInterruptControl, Priority}, + prelude::*, timer::{timg::TimerGroup, ErasedTimer}, }; use esp_hal_embassy::InterruptExecutor; diff --git a/examples/src/bin/embassy_serial.rs b/examples/src/bin/embassy_serial.rs index 8b47ce314e8..b923f384f1b 100644 --- a/examples/src/bin/embassy_serial.rs +++ b/examples/src/bin/embassy_serial.rs @@ -15,9 +15,10 @@ use esp_backtrace as _; use esp_hal::{ gpio::Io, peripherals::UART0, + prelude::*, timer::timg::TimerGroup, uart::{ - config::{AtCmdConfig, Config}, + config::{AtCmdConfig, Config as UartConfig}, Uart, UartRx, UartTx, @@ -102,7 +103,7 @@ async fn main(spawner: Spawner) { } } - let config = Config::default().rx_fifo_full_threshold(READ_BUF_SIZE as u16); + let config = UartConfig::default().rx_fifo_full_threshold(READ_BUF_SIZE as u16); let mut uart0 = Uart::new_async_with_config(peripherals.UART0, config, &clocks, tx_pin, rx_pin).unwrap(); diff --git a/examples/src/bin/embassy_touch.rs b/examples/src/bin/embassy_touch.rs index 25e28169a54..190bfda1927 100644 --- a/examples/src/bin/embassy_touch.rs +++ b/examples/src/bin/embassy_touch.rs @@ -18,6 +18,7 @@ use embassy_time::{Duration, Timer}; use esp_backtrace as _; use esp_hal::{ gpio::Io, + prelude::*, rtc_cntl::Rtc, timer::timg::TimerGroup, touch::{Touch, TouchConfig, TouchPad}, diff --git a/examples/src/bin/embassy_twai.rs b/examples/src/bin/embassy_twai.rs index 4740af9a861..e61e47c4080 100644 --- a/examples/src/bin/embassy_twai.rs +++ b/examples/src/bin/embassy_twai.rs @@ -28,6 +28,7 @@ use esp_hal::{ gpio::Io, interrupt, peripherals::{self, TWAI0}, + prelude::*, timer::timg::TimerGroup, twai::{self, EspTwaiFrame, TwaiMode, TwaiRx, TwaiTx}, }; diff --git a/examples/src/bin/embassy_usb_serial.rs b/examples/src/bin/embassy_usb_serial.rs index 0e1734b4e0f..422b43b258d 100644 --- a/examples/src/bin/embassy_usb_serial.rs +++ b/examples/src/bin/embassy_usb_serial.rs @@ -23,9 +23,10 @@ use esp_backtrace as _; use esp_hal::{ gpio::Io, otg_fs::{ - asynch::{Config, Driver}, + asynch::{Config as OtgConfig, Driver}, Usb, }, + prelude::*, timer::timg::TimerGroup, }; @@ -43,7 +44,7 @@ async fn main(_spawner: Spawner) -> () { // Create the driver, from the HAL. let mut ep_out_buffer = [0u8; 1024]; - let config = Config::default(); + let config = OtgConfig::default(); let driver = Driver::new(usb, &mut ep_out_buffer, config); diff --git a/examples/src/bin/embassy_usb_serial_jtag.rs b/examples/src/bin/embassy_usb_serial_jtag.rs index 5b784c0f90a..293a1b3d317 100644 --- a/examples/src/bin/embassy_usb_serial_jtag.rs +++ b/examples/src/bin/embassy_usb_serial_jtag.rs @@ -12,6 +12,7 @@ use embassy_executor::Spawner; use embassy_sync::{blocking_mutex::raw::NoopRawMutex, signal::Signal}; use esp_backtrace as _; use esp_hal::{ + prelude::*, timer::timg::TimerGroup, usb_serial_jtag::{UsbSerialJtag, UsbSerialJtagRx, UsbSerialJtagTx}, Async, diff --git a/examples/src/bin/embassy_wait.rs b/examples/src/bin/embassy_wait.rs index f8667a38392..86d69ceeab3 100644 --- a/examples/src/bin/embassy_wait.rs +++ b/examples/src/bin/embassy_wait.rs @@ -13,6 +13,7 @@ use embassy_time::{Duration, Timer}; use esp_backtrace as _; use esp_hal::{ gpio::{Input, Io, Pull}, + prelude::*, timer::timg::TimerGroup, }; @@ -25,10 +26,14 @@ async fn main(_spawner: Spawner) { esp_hal_embassy::init(&clocks, timg0.timer0); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); - #[cfg(any(feature = "esp32", feature = "esp32s2", feature = "esp32s3"))] - let mut input = Input::new(io.pins.gpio0, Pull::Down); - #[cfg(not(any(feature = "esp32", feature = "esp32s2", feature = "esp32s3")))] - let mut input = Input::new(io.pins.gpio9, Pull::Down); + + cfg_if::cfg_if! { + if #[cfg(any(feature = "esp32", feature = "esp32s2", feature = "esp32s3"))] { + let mut input = Input::new(io.pins.gpio0, Pull::Down); + } else { + let mut input = Input::new(io.pins.gpio9, Pull::Down); + } + } loop { esp_println::println!("Waiting..."); diff --git a/examples/src/bin/ieee802154_receive_all_frames.rs b/examples/src/bin/ieee802154_receive_all_frames.rs index 583503c69fb..f623dec8b2d 100644 --- a/examples/src/bin/ieee802154_receive_all_frames.rs +++ b/examples/src/bin/ieee802154_receive_all_frames.rs @@ -5,21 +5,21 @@ use esp_backtrace as _; use esp_hal::prelude::*; -use esp_ieee802154::*; +use esp_ieee802154::{Config as Ieee802154Config, Ieee802154}; use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (mut peripherals, _clocks) = esp_hal::init(Config::default()); let mut ieee802154 = Ieee802154::new(peripherals.IEEE802154, &mut peripherals.RADIO_CLK); - ieee802154.set_config(Config { + ieee802154.set_config(Ieee802154Config { channel: 15, promiscuous: true, rx_when_idle: true, auto_ack_rx: false, auto_ack_tx: false, - ..Config::default() + ..Default::default() }); println!("Start receiving:"); diff --git a/examples/src/bin/ieee802154_receive_frame.rs b/examples/src/bin/ieee802154_receive_frame.rs index 723153a877b..19ed94219d5 100644 --- a/examples/src/bin/ieee802154_receive_frame.rs +++ b/examples/src/bin/ieee802154_receive_frame.rs @@ -5,7 +5,7 @@ use esp_backtrace as _; use esp_hal::prelude::*; -use esp_ieee802154::*; +use esp_ieee802154::{Config as Ieee802154Config, Ieee802154}; use esp_println::println; #[entry] @@ -13,7 +13,7 @@ fn main() -> ! { let (mut peripherals, _clocks) = esp_hal::init(Config::default()); let mut ieee802154 = Ieee802154::new(peripherals.IEEE802154, &mut peripherals.RADIO_CLK); - ieee802154.set_config(Config { + ieee802154.set_config(Ieee802154Config { channel: 15, promiscuous: false, rx_when_idle: true, @@ -21,7 +21,7 @@ fn main() -> ! { auto_ack_tx: true, pan_id: Some(0x4242), short_addr: Some(0x2323), - ..Config::default() + ..Default::default() }); println!("Start receiving:"); diff --git a/examples/src/bin/ieee802154_send_broadcast_frame.rs b/examples/src/bin/ieee802154_send_broadcast_frame.rs index 9b04f678391..3ee1f554862 100644 --- a/examples/src/bin/ieee802154_send_broadcast_frame.rs +++ b/examples/src/bin/ieee802154_send_broadcast_frame.rs @@ -5,7 +5,7 @@ use esp_backtrace as _; use esp_hal::{delay::Delay, prelude::*}; -use esp_ieee802154::*; +use esp_ieee802154::{Config as Ieee802154Config, Frame, Ieee802154}; use esp_println::println; use ieee802154::mac::{ Address, @@ -25,12 +25,12 @@ fn main() -> ! { let mut ieee802154 = Ieee802154::new(peripherals.IEEE802154, &mut peripherals.RADIO_CLK); - ieee802154.set_config(Config { + ieee802154.set_config(Ieee802154Config { channel: 15, promiscuous: false, pan_id: Some(0x4242), short_addr: Some(0x2323), - ..Config::default() + ..Default::default() }); let mut seq_number = 0u8; diff --git a/examples/src/bin/ieee802154_send_frame.rs b/examples/src/bin/ieee802154_send_frame.rs index 15297085d15..944688784a7 100644 --- a/examples/src/bin/ieee802154_send_frame.rs +++ b/examples/src/bin/ieee802154_send_frame.rs @@ -5,7 +5,7 @@ use esp_backtrace as _; use esp_hal::{delay::Delay, prelude::*}; -use esp_ieee802154::*; +use esp_ieee802154::{Config as Ieee802154Config, Frame, Ieee802154}; use esp_println::println; use ieee802154::mac::{ Address, @@ -25,12 +25,12 @@ fn main() -> ! { let mut ieee802154 = Ieee802154::new(peripherals.IEEE802154, &mut peripherals.RADIO_CLK); - ieee802154.set_config(Config { + ieee802154.set_config(Ieee802154Config { channel: 15, promiscuous: false, pan_id: Some(0x4242), short_addr: Some(0x2222), - ..Config::default() + ..Default::default() }); let mut seq_number = 0u8; diff --git a/examples/src/bin/ieee802154_sniffer.rs b/examples/src/bin/ieee802154_sniffer.rs index ae1102fdcac..68e2e98c7f5 100644 --- a/examples/src/bin/ieee802154_sniffer.rs +++ b/examples/src/bin/ieee802154_sniffer.rs @@ -9,7 +9,7 @@ use esp_backtrace as _; use esp_hal::{gpio::Io, prelude::*, reset::software_reset, uart::Uart}; -use esp_ieee802154::*; +use esp_ieee802154::{Config as Ieee802154Config, Ieee802154}; use esp_println::println; #[entry] @@ -53,13 +53,13 @@ fn main() -> ! { let radio = peripherals.IEEE802154; let mut ieee802154 = Ieee802154::new(radio, &mut peripherals.RADIO_CLK); - ieee802154.set_config(Config { + ieee802154.set_config(Ieee802154Config { channel, promiscuous: true, rx_when_idle: true, auto_ack_rx: false, auto_ack_tx: false, - ..Config::default() + ..Default::default() }); ieee802154.start_receive(); diff --git a/examples/src/bin/lcd_i8080.rs b/examples/src/bin/lcd_i8080.rs index 19262cc3586..6bcce17e26c 100644 --- a/examples/src/bin/lcd_i8080.rs +++ b/examples/src/bin/lcd_i8080.rs @@ -28,7 +28,7 @@ use esp_hal::{ dma_buffers, gpio::{Io, Level, Output}, lcd_cam::{ - lcd::i8080::{Config, TxEightBits, I8080}, + lcd::i8080::{self, TxEightBits, I8080}, LcdCam, }, prelude::*, @@ -77,7 +77,7 @@ fn main() -> ! { tx_descriptors, tx_pins, 20.MHz(), - Config::default(), + i8080::Config::default(), &clocks, ) .with_ctrl_pins(lcd_rs, lcd_wr); diff --git a/examples/src/bin/lp_core_uart.rs b/examples/src/bin/lp_core_uart.rs index 4a8431e2447..6296c9813d7 100644 --- a/examples/src/bin/lp_core_uart.rs +++ b/examples/src/bin/lp_core_uart.rs @@ -22,7 +22,7 @@ use esp_hal::{ }, lp_core::{LpCore, LpCoreWakeupSource}, prelude::*, - uart::{config::Config, lp_uart::LpUart, Uart}, + uart::{config::Config as UartConfig, lp_uart::LpUart, Uart}, }; use esp_println::println; @@ -36,7 +36,7 @@ fn main() -> ! { let mut uart1 = Uart::new_with_config( peripherals.UART1, - Config::default(), + UartConfig::default(), &clocks, io.pins.gpio6, io.pins.gpio7, diff --git a/examples/src/bin/psram_quad.rs b/examples/src/bin/psram_quad.rs index 3037206f091..cf11cbc87da 100644 --- a/examples/src/bin/psram_quad.rs +++ b/examples/src/bin/psram_quad.rs @@ -13,7 +13,7 @@ extern crate alloc; use alloc::{string::String, vec::Vec}; use esp_backtrace as _; -use esp_hal::{clock::ClockControl, prelude::*, psram}; +use esp_hal::{prelude::*, psram}; use esp_println::println; #[global_allocator] diff --git a/examples/src/bin/serial_interrupts.rs b/examples/src/bin/serial_interrupts.rs index 2985b75dd6c..901ac58c4b1 100644 --- a/examples/src/bin/serial_interrupts.rs +++ b/examples/src/bin/serial_interrupts.rs @@ -17,7 +17,7 @@ use esp_hal::{ peripherals::UART0, prelude::*, uart::{ - config::{AtCmdConfig, Config}, + config::{AtCmdConfig, Config as UartConfig}, Uart, }, Blocking, @@ -49,7 +49,7 @@ fn main() -> ! { let (tx_pin, rx_pin) = (io.pins.gpio43, io.pins.gpio44); } } - let config = Config::default().rx_fifo_full_threshold(30); + let config = UartConfig::default().rx_fifo_full_threshold(30); let mut uart0 = Uart::new_with_config(peripherals.UART0, config, &clocks, tx_pin, rx_pin).unwrap(); diff --git a/examples/src/bin/sleep_timer.rs b/examples/src/bin/sleep_timer.rs index 9296fd7df52..1e9cbe2a29f 100644 --- a/examples/src/bin/sleep_timer.rs +++ b/examples/src/bin/sleep_timer.rs @@ -11,6 +11,7 @@ use esp_backtrace as _; use esp_hal::{ delay::Delay, entry, + prelude::*, rtc_cntl::{get_reset_reason, get_wakeup_cause, sleep::TimerWakeupSource, Rtc, SocResetReason}, Cpu, }; diff --git a/examples/src/bin/sleep_timer_ext0.rs b/examples/src/bin/sleep_timer_ext0.rs index bd6576fc83d..7b9f62f1ae5 100644 --- a/examples/src/bin/sleep_timer_ext0.rs +++ b/examples/src/bin/sleep_timer_ext0.rs @@ -15,6 +15,7 @@ use esp_hal::{ delay::Delay, entry, gpio::Io, + prelude::*, rtc_cntl::{ get_reset_reason, get_wakeup_cause, diff --git a/examples/src/bin/sleep_timer_ext1.rs b/examples/src/bin/sleep_timer_ext1.rs index 7aacd563372..7add24dfa99 100644 --- a/examples/src/bin/sleep_timer_ext1.rs +++ b/examples/src/bin/sleep_timer_ext1.rs @@ -15,6 +15,7 @@ use esp_hal::{ delay::Delay, entry, gpio::{Io, RtcPin}, + prelude::*, rtc_cntl::{ get_reset_reason, get_wakeup_cause, diff --git a/examples/src/bin/sleep_timer_lpio.rs b/examples/src/bin/sleep_timer_lpio.rs index cba6153aaa7..136f9d3b900 100644 --- a/examples/src/bin/sleep_timer_lpio.rs +++ b/examples/src/bin/sleep_timer_lpio.rs @@ -16,6 +16,7 @@ use esp_hal::{ delay::Delay, entry, gpio::{Io, RtcPinWithResistors}, + prelude::*, rtc_cntl::{ get_reset_reason, get_wakeup_cause, diff --git a/examples/src/bin/sleep_timer_rtcio.rs b/examples/src/bin/sleep_timer_rtcio.rs index 8588159b700..47df5af827f 100644 --- a/examples/src/bin/sleep_timer_rtcio.rs +++ b/examples/src/bin/sleep_timer_rtcio.rs @@ -20,6 +20,7 @@ use esp_hal::{ entry, gpio, gpio::Io, + prelude::*, rtc_cntl::{ get_reset_reason, get_wakeup_cause, diff --git a/examples/src/bin/software_interrupts.rs b/examples/src/bin/software_interrupts.rs index 44c655ec9db..a26eadd9392 100644 --- a/examples/src/bin/software_interrupts.rs +++ b/examples/src/bin/software_interrupts.rs @@ -15,7 +15,7 @@ use critical_section::Mutex; use esp_backtrace as _; use esp_hal::{ delay::Delay, - interrupt::interrupt::software::{SoftwareInterrupt, SoftwareInterruptControl}, + interrupt::software::{SoftwareInterrupt, SoftwareInterruptControl}, prelude::*, }; @@ -31,33 +31,33 @@ fn main() -> ! { let mut sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); critical_section::with(|cs| { - sw_int + sw_ints .software_interrupt0 .set_interrupt_handler(swint0_handler); SWINT0 .borrow_ref_mut(cs) - .replace(sw_int.software_interrupt0); + .replace(sw_ints.software_interrupt0); - sw_int + sw_ints .software_interrupt1 .set_interrupt_handler(swint1_handler); SWINT1 .borrow_ref_mut(cs) - .replace(sw_int.software_interrupt1); + .replace(sw_ints.software_interrupt1); - sw_int + sw_ints .software_interrupt2 .set_interrupt_handler(swint2_handler); SWINT2 .borrow_ref_mut(cs) - .replace(sw_int.software_interrupt2); + .replace(sw_ints.software_interrupt2); - sw_int + sw_ints .software_interrupt3 .set_interrupt_handler(swint3_handler); SWINT3 .borrow_ref_mut(cs) - .replace(sw_int.software_interrupt3); + .replace(sw_ints.software_interrupt3); }); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/spi_loopback_dma.rs b/examples/src/bin/spi_loopback_dma.rs index 3737936cd96..419d1ea46ff 100644 --- a/examples/src/bin/spi_loopback_dma.rs +++ b/examples/src/bin/spi_loopback_dma.rs @@ -20,15 +20,12 @@ use esp_backtrace as _; use esp_hal::{ - clock::ClockControl, delay::Delay, dma::{Dma, DmaPriority, DmaRxBuf, DmaTxBuf}, dma_buffers, gpio::Io, - peripherals::Peripherals, prelude::*, spi::{master::Spi, SpiMode}, - system::SystemControl, }; use esp_println::println; diff --git a/examples/src/bin/wifi_ble.rs b/examples/src/bin/wifi_ble.rs index 13558d6697b..105034d8192 100644 --- a/examples/src/bin/wifi_ble.rs +++ b/examples/src/bin/wifi_ble.rs @@ -25,7 +25,6 @@ use bleps::{ use esp_backtrace as _; use esp_hal::{ gpio::{Input, Io, Pull}, - peripherals::*, prelude::*, rng::Rng, timer::timg::TimerGroup, diff --git a/examples/src/bin/wifi_embassy_access_point.rs b/examples/src/bin/wifi_embassy_access_point.rs index 1208244f0bf..4cda2e8cc98 100644 --- a/examples/src/bin/wifi_embassy_access_point.rs +++ b/examples/src/bin/wifi_embassy_access_point.rs @@ -17,7 +17,6 @@ use embassy_executor::Spawner; use embassy_net::{ tcp::TcpSocket, - Config, IpListenEndpoint, Ipv4Address, Ipv4Cidr, @@ -27,7 +26,7 @@ use embassy_net::{ }; use embassy_time::{Duration, Timer}; use esp_backtrace as _; -use esp_hal::{rng::Rng, timer::timg::TimerGroup}; +use esp_hal::{prelude::*, rng::Rng, timer::timg::TimerGroup}; use esp_println::{print, println}; use esp_wifi::{ initialize, @@ -88,7 +87,7 @@ async fn main(spawner: Spawner) -> ! { } } - let config = Config::ipv4_static(StaticConfigV4 { + let config = embassy_net::Config::ipv4_static(StaticConfigV4 { address: Ipv4Cidr::new(Ipv4Address::new(192, 168, 2, 1), 24), gateway: Some(Ipv4Address::from_bytes(&[192, 168, 2, 1])), dns_servers: Default::default(), diff --git a/examples/src/bin/wifi_embassy_access_point_with_sta.rs b/examples/src/bin/wifi_embassy_access_point_with_sta.rs index 733a035093f..4524aa76368 100644 --- a/examples/src/bin/wifi_embassy_access_point_with_sta.rs +++ b/examples/src/bin/wifi_embassy_access_point_with_sta.rs @@ -20,7 +20,6 @@ use embassy_executor::Spawner; use embassy_net::{ tcp::TcpSocket, - Config, IpListenEndpoint, Ipv4Address, Ipv4Cidr, @@ -30,13 +29,7 @@ use embassy_net::{ }; use embassy_time::{Duration, Timer}; use esp_backtrace as _; -use esp_hal::{ - clock::ClockControl, - peripherals::Peripherals, - rng::Rng, - system::SystemControl, - timer::timg::TimerGroup, -}; +use esp_hal::{prelude::*, rng::Rng, timer::timg::TimerGroup}; use esp_println::{print, println}; use esp_wifi::{ initialize, @@ -102,12 +95,12 @@ async fn main(spawner: Spawner) -> ! { } } - let ap_config = Config::ipv4_static(StaticConfigV4 { + let ap_config = embassy_net::Config::ipv4_static(StaticConfigV4 { address: Ipv4Cidr::new(Ipv4Address::new(192, 168, 2, 1), 24), gateway: Some(Ipv4Address::from_bytes(&[192, 168, 2, 1])), dns_servers: Default::default(), }); - let sta_config = Config::dhcpv4(Default::default()); + let sta_config = embassy_net::Config::dhcpv4(Default::default()); let seed = 1234; // very random, very secure seed diff --git a/examples/src/bin/wifi_embassy_bench.rs b/examples/src/bin/wifi_embassy_bench.rs index 2db24497831..661e5f7eb83 100644 --- a/examples/src/bin/wifi_embassy_bench.rs +++ b/examples/src/bin/wifi_embassy_bench.rs @@ -18,10 +18,10 @@ use embassy_executor::Spawner; use embassy_futures::join::join; -use embassy_net::{tcp::TcpSocket, Config, Ipv4Address, Stack, StackResources}; +use embassy_net::{tcp::TcpSocket, Ipv4Address, Stack, StackResources}; use embassy_time::{with_timeout, Duration, Timer}; use esp_backtrace as _; -use esp_hal::{rng::Rng, timer::timg::TimerGroup}; +use esp_hal::{prelude::*, rng::Rng, timer::timg::TimerGroup}; use esp_println::println; use esp_wifi::{ initialize, @@ -100,7 +100,7 @@ async fn main(spawner: Spawner) -> ! { } } - let config = Config::dhcpv4(Default::default()); + let config = embassy_net::Config::dhcpv4(Default::default()); let seed = 1234; // very random, very secure seed diff --git a/examples/src/bin/wifi_embassy_ble.rs b/examples/src/bin/wifi_embassy_ble.rs index 559cf1ed490..52dc06c4446 100644 --- a/examples/src/bin/wifi_embassy_ble.rs +++ b/examples/src/bin/wifi_embassy_ble.rs @@ -28,7 +28,7 @@ use embassy_executor::Spawner; use esp_backtrace as _; use esp_hal::{ gpio::{Input, Io, Pull}, - peripherals::*, + prelude::*, rng::Rng, timer::timg::TimerGroup, }; diff --git a/examples/src/bin/wifi_embassy_dhcp.rs b/examples/src/bin/wifi_embassy_dhcp.rs index 789ac88964a..dfc3cc072c4 100644 --- a/examples/src/bin/wifi_embassy_dhcp.rs +++ b/examples/src/bin/wifi_embassy_dhcp.rs @@ -14,10 +14,10 @@ #![no_main] use embassy_executor::Spawner; -use embassy_net::{tcp::TcpSocket, Config, Ipv4Address, Stack, StackResources}; +use embassy_net::{tcp::TcpSocket, Ipv4Address, Stack, StackResources}; use embassy_time::{Duration, Timer}; use esp_backtrace as _; -use esp_hal::{rng::Rng, timer::timg::TimerGroup}; +use esp_hal::{prelude::*, rng::Rng, timer::timg::TimerGroup}; use esp_println::println; use esp_wifi::{ initialize, @@ -81,7 +81,7 @@ async fn main(spawner: Spawner) -> ! { } } - let config = Config::dhcpv4(Default::default()); + let config = embassy_net::Config::dhcpv4(Default::default()); let seed = 1234; // very random, very secure seed diff --git a/examples/src/bin/wifi_embassy_esp_now.rs b/examples/src/bin/wifi_embassy_esp_now.rs index cf23adf050b..743c4b66587 100644 --- a/examples/src/bin/wifi_embassy_esp_now.rs +++ b/examples/src/bin/wifi_embassy_esp_now.rs @@ -14,7 +14,7 @@ use embassy_executor::Spawner; use embassy_futures::select::{select, Either}; use embassy_time::{Duration, Ticker}; use esp_backtrace as _; -use esp_hal::{rng::Rng, timer::timg::TimerGroup}; +use esp_hal::{prelude::*, rng::Rng, timer::timg::TimerGroup}; use esp_println::println; use esp_wifi::{ esp_now::{PeerInfo, BROADCAST_ADDRESS}, diff --git a/examples/src/bin/wifi_embassy_esp_now_duplex.rs b/examples/src/bin/wifi_embassy_esp_now_duplex.rs index 027fc3d5db7..f994e26a7f4 100644 --- a/examples/src/bin/wifi_embassy_esp_now_duplex.rs +++ b/examples/src/bin/wifi_embassy_esp_now_duplex.rs @@ -14,7 +14,7 @@ use embassy_executor::Spawner; use embassy_sync::{blocking_mutex::raw::NoopRawMutex, mutex::Mutex}; use embassy_time::{Duration, Ticker}; use esp_backtrace as _; -use esp_hal::{rng::Rng, timer::timg::TimerGroup}; +use esp_hal::{prelude::*, rng::Rng, timer::timg::TimerGroup}; use esp_println::println; use esp_wifi::{ esp_now::{EspNowManager, EspNowReceiver, EspNowSender, PeerInfo, BROADCAST_ADDRESS}, diff --git a/hil-test/tests/aes_dma.rs b/hil-test/tests/aes_dma.rs index e36cfa3ec37..2bc940a9899 100644 --- a/hil-test/tests/aes_dma.rs +++ b/hil-test/tests/aes_dma.rs @@ -29,7 +29,7 @@ mod tests { #[init] fn init() -> Peripherals { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); peripherals } diff --git a/hil-test/tests/clock_monitor.rs b/hil-test/tests/clock_monitor.rs index f1ecc9de08f..de3a94bdc72 100644 --- a/hil-test/tests/clock_monitor.rs +++ b/hil-test/tests/clock_monitor.rs @@ -12,15 +12,6 @@ struct Context<'a> { rtc: Rtc<'a>, } -impl Context<'_> { - pub fn init() -> Self { - let (peripherals, clocks) = esp_hal::init(Config::default()); - let rtc = Rtc::new(peripherals.LPWR); - - Context { rtc } - } -} - #[cfg(test)] #[embedded_test::tests] mod tests { @@ -28,7 +19,10 @@ mod tests { #[init] fn init() -> Context<'static> { - Context::init() + let (peripherals, _clocks) = esp_hal::init(Config::default()); + let rtc = Rtc::new(peripherals.LPWR); + + Context { rtc } } #[test] diff --git a/hil-test/tests/dma_mem2mem.rs b/hil-test/tests/dma_mem2mem.rs index 22d41234f73..14878ac4685 100644 --- a/hil-test/tests/dma_mem2mem.rs +++ b/hil-test/tests/dma_mem2mem.rs @@ -39,7 +39,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(Config::default()); let dma = Dma::new(peripherals.DMA); let channel = dma.channel0.configure(false, DmaPriority::Priority0); diff --git a/hil-test/tests/embassy_interrupt_executor.rs b/hil-test/tests/embassy_interrupt_executor.rs index 078d339b451..117f78ca784 100644 --- a/hil-test/tests/embassy_interrupt_executor.rs +++ b/hil-test/tests/embassy_interrupt_executor.rs @@ -10,7 +10,6 @@ use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, signal::Signal}; use esp_hal::{ - clock::CpuClock, interrupt::{ software::{SoftwareInterrupt, SoftwareInterruptControl}, Priority, diff --git a/hil-test/tests/sha.rs b/hil-test/tests/sha.rs index 327824e931e..91278c5d0ef 100644 --- a/hil-test/tests/sha.rs +++ b/hil-test/tests/sha.rs @@ -13,7 +13,6 @@ use esp_hal::sha::{Sha384, Sha512}; #[cfg(any(feature = "esp32s2", feature = "esp32s3"))] use esp_hal::sha::{Sha512_224, Sha512_256}; use esp_hal::{ - peripherals::Peripherals, prelude::*, rng::Rng, sha::{Sha, Sha1, Sha256}, @@ -84,6 +83,7 @@ fn assert_digest(input: &[u8]) { } } +#[allow(unused_mut)] fn with_random_data( mut rng: Rng, f: impl Fn( @@ -97,7 +97,6 @@ fn with_random_data( const BUFFER_LEN: usize = 256; let mut sha1_random = [0u8; BUFFER_LEN]; - #[cfg_attr(feature = "esp32", allow(unused_mut))] let mut sha224_random = [0u8; BUFFER_LEN]; let mut sha256_random = [0u8; BUFFER_LEN]; let mut sha384_random = [0u8; BUFFER_LEN]; @@ -157,6 +156,7 @@ fn with_random_data( #[cfg(test)] #[embedded_test::tests] mod tests { + #[cfg(any(feature = "esp32s2", feature = "esp32s3"))] use defmt::assert_eq; use super::*; diff --git a/hil-test/tests/spi_full_duplex_dma.rs b/hil-test/tests/spi_full_duplex_dma.rs index 5c9ed59aa97..0081267a0cf 100644 --- a/hil-test/tests/spi_full_duplex_dma.rs +++ b/hil-test/tests/spi_full_duplex_dma.rs @@ -14,18 +14,17 @@ #![no_main] use esp_hal::{ - clock::{ClockControl, Clocks}, + clock::Clocks, dma::{Dma, DmaPriority, DmaRxBuf, DmaTxBuf}, dma_buffers, gpio::Io, - peripherals::{Peripherals, SPI2}, + peripherals::SPI2, prelude::*, spi::{ master::{Spi, SpiDma}, FullDuplexMode, SpiMode, }, - system::SystemControl, Blocking, }; use hil_test as _; diff --git a/hil-test/tests/spi_full_duplex_dma_async.rs b/hil-test/tests/spi_full_duplex_dma_async.rs index 61b0976e03c..7159e8a7726 100644 --- a/hil-test/tests/spi_full_duplex_dma_async.rs +++ b/hil-test/tests/spi_full_duplex_dma_async.rs @@ -22,7 +22,6 @@ use embedded_hal_async::spi::SpiBus; use esp_hal::{ - clock::{ClockControl, Clocks}, dma::{Dma, DmaPriority, DmaRxBuf, DmaTxBuf}, dma_buffers, gpio::{GpioPin, Io, Level, Output, Pull}, @@ -31,14 +30,13 @@ use esp_hal::{ unit::Unit, Pcnt, }, - peripherals::{Peripherals, SPI2}, + peripherals::SPI2, prelude::*, spi::{ master::{Spi, SpiDmaBus}, FullDuplexMode, SpiMode, }, - system::SystemControl, Async, }; use hil_test as _; diff --git a/hil-test/tests/spi_full_duplex_dma_pcnt.rs b/hil-test/tests/spi_full_duplex_dma_pcnt.rs index 50e78fea918..6fb816a0efc 100644 --- a/hil-test/tests/spi_full_duplex_dma_pcnt.rs +++ b/hil-test/tests/spi_full_duplex_dma_pcnt.rs @@ -18,7 +18,6 @@ #![no_main] use esp_hal::{ - clock::ClockControl, dma::{Dma, DmaPriority, DmaRxBuf, DmaTxBuf}, dma_buffers, gpio::{GpioPin, Io, Level, Output, Pull}, @@ -27,14 +26,13 @@ use esp_hal::{ unit::Unit, Pcnt, }, - peripherals::{Peripherals, SPI2}, + peripherals::SPI2, prelude::*, spi::{ master::{Spi, SpiDma}, FullDuplexMode, SpiMode, }, - system::SystemControl, Blocking, }; use hil_test as _; @@ -66,9 +64,7 @@ mod tests { #[init] fn init() -> Context { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let (peripherals, clocks) = esp_hal::init(Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/spi_half_duplex_read.rs b/hil-test/tests/spi_half_duplex_read.rs index 6048c1bccf1..6d036f1f540 100644 --- a/hil-test/tests/spi_half_duplex_read.rs +++ b/hil-test/tests/spi_half_duplex_read.rs @@ -14,11 +14,10 @@ #![no_main] use esp_hal::{ - clock::ClockControl, dma::{Dma, DmaPriority, DmaRxBuf, DmaTxBuf}, dma_buffers, gpio::{GpioPin, Io, Level, Output}, - peripherals::{Peripherals, SPI2}, + peripherals::SPI2, prelude::*, spi::{ master::{Address, Command, HalfDuplexReadWrite, Spi, SpiDma}, @@ -26,7 +25,6 @@ use esp_hal::{ SpiDataMode, SpiMode, }, - system::SystemControl, Blocking, }; use hil_test as _; diff --git a/hil-test/tests/spi_half_duplex_write.rs b/hil-test/tests/spi_half_duplex_write.rs index 36bafdc1f9f..2185b252eaa 100644 --- a/hil-test/tests/spi_half_duplex_write.rs +++ b/hil-test/tests/spi_half_duplex_write.rs @@ -14,7 +14,6 @@ #![no_main] use esp_hal::{ - clock::ClockControl, dma::{Dma, DmaPriority, DmaRxBuf, DmaTxBuf}, dma_buffers, gpio::{GpioPin, Io, Pull}, @@ -23,7 +22,7 @@ use esp_hal::{ unit::Unit, Pcnt, }, - peripherals::{Peripherals, SPI2}, + peripherals::SPI2, prelude::*, spi::{ master::{Address, Command, HalfDuplexReadWrite, Spi, SpiDma}, @@ -31,7 +30,6 @@ use esp_hal::{ SpiDataMode, SpiMode, }, - system::SystemControl, Blocking, }; use hil_test as _; From 4d3629f01464426af05c8acd2e09cd4649681505 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Wed, 28 Aug 2024 17:17:04 +0200 Subject: [PATCH 15/19] Update tests --- hil-test/tests/aes.rs | 22 ++++++++-------------- hil-test/tests/delay.rs | 14 ++++---------- hil-test/tests/gpio.rs | 39 +++++++++++++++------------------------ 3 files changed, 27 insertions(+), 48 deletions(-) diff --git a/hil-test/tests/aes.rs b/hil-test/tests/aes.rs index 1bc59f031e7..00cfcdbedb2 100644 --- a/hil-test/tests/aes.rs +++ b/hil-test/tests/aes.rs @@ -15,19 +15,6 @@ struct Context<'a> { aes: Aes<'a>, } -impl Context<'_> { - pub fn init() -> Self { - let (peripherals, _clocks) = esp_hal::init({ - let mut config = Config::default(); - config.cpu_clock = CpuClock::max(); - config - }); - let aes = Aes::new(peripherals.AES); - - Context { aes } - } -} - #[cfg(test)] #[embedded_test::tests] mod tests { @@ -37,7 +24,14 @@ mod tests { #[init] fn init() -> Context<'static> { - Context::init() + let (peripherals, _clocks) = esp_hal::init({ + let mut config = Config::default(); + config.cpu_clock = CpuClock::max(); + config + }); + let aes = Aes::new(peripherals.AES); + + Context { aes } } #[test] diff --git a/hil-test/tests/delay.rs b/hil-test/tests/delay.rs index 2ce0448d98e..8058574f2cb 100644 --- a/hil-test/tests/delay.rs +++ b/hil-test/tests/delay.rs @@ -13,15 +13,6 @@ struct Context { delay: Delay, } -impl Context { - pub fn init() -> Self { - let (peripherals, clocks) = esp_hal::init(Config::default()); - let delay = Delay::new(&clocks); - - Context { delay } - } -} - #[cfg(test)] #[embedded_test::tests] mod tests { @@ -29,7 +20,10 @@ mod tests { #[init] fn init() -> Context { - Context::init() + let (peripherals, clocks) = esp_hal::init(Config::default()); + let delay = Delay::new(&clocks); + + Context { delay } } #[test] diff --git a/hil-test/tests/gpio.rs b/hil-test/tests/gpio.rs index b20709ceca6..bbc97fbafd8 100644 --- a/hil-test/tests/gpio.rs +++ b/hil-test/tests/gpio.rs @@ -32,26 +32,6 @@ struct Context<'d> { delay: Delay, } -impl<'d> Context<'d> { - pub fn init() -> Self { - let (peripherals, clocks) = esp_hal::init(Config::default()); - - let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); - io.set_interrupt_handler(interrupt_handler); - - let delay = Delay::new(&clocks); - - let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); - esp_hal_embassy::init(&clocks, timg0.timer0); - - Context { - io2: Input::new(io.pins.gpio2, Pull::Down), - io3: Output::new(io.pins.gpio3, Level::Low), - delay, - } - } -} - #[handler] pub fn interrupt_handler() { critical_section::with(|cs| { @@ -75,10 +55,21 @@ mod tests { #[init] fn init() -> Context<'static> { - let mut ctx = Context::init(); - // make sure tests don't interfere with each other - ctx.io3.set_low(); - ctx + let (peripherals, clocks) = esp_hal::init(Config::default()); + + let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); + io.set_interrupt_handler(interrupt_handler); + + let delay = Delay::new(&clocks); + + let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); + esp_hal_embassy::init(&clocks, timg0.timer0); + + Context { + io2: Input::new(io.pins.gpio2, Pull::Down), + io3: Output::new(io.pins.gpio3, Level::Low), + delay, + } } #[test] From d3248d65432fcfb6cca508c61b2fae73a912342b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Fri, 30 Aug 2024 14:51:04 +0200 Subject: [PATCH 16/19] Add changelog entry --- esp-hal/CHANGELOG.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/esp-hal/CHANGELOG.md b/esp-hal/CHANGELOG.md index ba3d30599b8..32441a10703 100644 --- a/esp-hal/CHANGELOG.md +++ b/esp-hal/CHANGELOG.md @@ -9,6 +9,8 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0 ### Added +- Added `esp_hal::init` to simplify HAL initialisation (#1970) + ### Changed ### Fixed From 78b265fc0bd2189b54f60341890e328f0ce7f7f8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Fri, 30 Aug 2024 15:27:45 +0200 Subject: [PATCH 17/19] Start migration guide --- .github/PULL_REQUEST_TEMPLATE.md | 1 + documentation/CONTRIBUTING.md | 8 +++++--- esp-hal/MIGRATING-0.20.md | 26 ++++++++++++++++++++++++++ 3 files changed, 32 insertions(+), 3 deletions(-) create mode 100644 esp-hal/MIGRATING-0.20.md diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md index 601f5094dcc..8ddc5827c73 100644 --- a/.github/PULL_REQUEST_TEMPLATE.md +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -7,6 +7,7 @@ To help us review it efficiently, please ensure you've gone through the followin - [ ] I have updated existing examples or added new ones (if applicable). - [ ] I have used `cargo xtask fmt-packages` command to ensure that all changed code is formatted correctly. - [ ] My changes were added to the [`CHANGELOG.md`](https://github.com/esp-rs/esp-hal/blob/main/esp-hal/CHANGELOG.md) in the **_proper_** section. +- [ ] I have added necessary changes to user code to the [Migration Guide](https://github.com/esp-rs/esp-hal/blob/main/esp-hal/MIGRATING-0.21.md). - [ ] My changes are in accordance to the [esp-rs API guidelines](https://github.com/esp-rs/esp-hal/blob/main/documentation/API-GUIDELINES.md) #### Extra: diff --git a/documentation/CONTRIBUTING.md b/documentation/CONTRIBUTING.md index e0abb806e07..0ce91dd0dcf 100644 --- a/documentation/CONTRIBUTING.md +++ b/documentation/CONTRIBUTING.md @@ -84,11 +84,11 @@ By taking these extra steps to test your contributions, you help maintain the hi Ensuring the quality and reliability of `esp-hal` is a shared responsibility, and testing plays a critical role in this process. Our GitHub CI automatically checks the buildability of all examples and drivers within the project. However, automated tests can't catch everything, especially when it comes to the nuanced behavior of hardware interactions. So make sure that the example affected by your change works as expected. -Further steps that can (or should) be taken in testing: +Further steps that can (or should) be taken in testing: -* Using [xtask], build examples for the specified chip. +* Using [xtask], build examples for the specified chip. * Build the documentation and run the doctests if they have been modified using the `build-documentation` and `run-doc-test` commands in [xtask]. -* Run the [HIL] tests locally if changes have been made to them. +* Run the [HIL] tests locally if changes have been made to them. [xtask]: https://github.com/esp-rs/esp-hal/tree/main/xtask @@ -122,6 +122,7 @@ This will use `rustfmt` to ensure that all source code is formatted correctly pr * [Link your PR] to any relevant issues it addresses. * [Allow edits from maintainers] so the branch can be updated for a merge. Once you submit your PR, a Docs team member will review your proposal. We may ask questions or request additional information. * Make sure you add an entry with your changes to the [Changelog]. Also make sure that it is in the appropriate section of the document. +* Make sure you add your changes to the current [migration guide]. * We may ask for changes to be made before a PR can be merged, either using [suggested changes] or pull request comments. You can apply suggested changes directly through the UI. You can make any other changes in your fork, then commit them to your branch. * As you update your PR and apply changes, mark each conversation as [resolved]. * Resolve merge conflicts if they arise, using resources like [this git tutorial] for help. @@ -129,6 +130,7 @@ This will use `rustfmt` to ensure that all source code is formatted correctly pr [Link your PR]: https://docs.github.com/en/issues/tracking-your-work-with-issues/linking-a-pull-request-to-an-issue [Allow edits from maintainers]: https://docs.github.com/en/pull-requests/collaborating-with-pull-requests/working-with-forks/allowing-changes-to-a-pull-request-branch-created-from-a-forkmember [Changelog]: esp-hal/CHANGELOG.md +[migration guide]: esp-hal/MIGRATING-0.20.md [suggested changes]: https://docs.github.com/en/pull-requests/collaborating-with-pull-requests/reviewing-changes-in-pull-requests/incorporating-feedback-in-your-pull-request [resolved]: https://docs.github.com/en/pull-requests/collaborating-with-pull-requests/reviewing-changes-in-pull-requests/commenting-on-a-pull-request#resolving-conversations [this git tutorial]: https://github.com/skills/resolve-merge-conflicts diff --git a/esp-hal/MIGRATING-0.20.md b/esp-hal/MIGRATING-0.20.md new file mode 100644 index 00000000000..d0eec4a8881 --- /dev/null +++ b/esp-hal/MIGRATING-0.20.md @@ -0,0 +1,26 @@ +Migration Guide from 0.20.x to vNext +==================================== + +HAL initialsation +----------------- + +Instead of manually grabbing peripherals and setting up clocks, you should now call `esp_hal::init`. + +```diff + use esp_hal::{ +- clock::ClockControl, +- peripherals::Peripherals, + prelude::*, +- system::SystemControl, + }; + + #[entry] + fn main() -> ! { +- let peripherals = Peripherals::take(); +- let system = SystemControl::new(peripherals.SYSTEM); +- let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); ++ let (peripherals, clocks) = esp_hal::init(Config::default()); + + // ... + } +``` From 84cc8bac0dca4a79e359797c68eb97f5d8f772ed Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Fri, 30 Aug 2024 16:07:21 +0200 Subject: [PATCH 18/19] Restore some convenience-imports --- esp-hal/src/lib.rs | 2 ++ 1 file changed, 2 insertions(+) diff --git a/esp-hal/src/lib.rs b/esp-hal/src/lib.rs index cf50c207770..9b98ac3e546 100644 --- a/esp-hal/src/lib.rs +++ b/esp-hal/src/lib.rs @@ -618,6 +618,8 @@ macro_rules! before_snippet { r#" # #![no_std] # use esp_hal::prelude::*; +# use procmacros::handler; +# use esp_hal::interrupt; # #[panic_handler] # fn panic(_ : &core::panic::PanicInfo) -> ! { # loop {} From a136d331e8e04d43e4842ee658336080a275cbb9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Mon, 2 Sep 2024 12:59:53 +0200 Subject: [PATCH 19/19] Remove Config from prelude --- esp-hal/MIGRATING-0.20.md | 2 +- esp-hal/src/clock/mod.rs | 6 +++--- esp-hal/src/lcd_cam/lcd/i8080.rs | 4 ++-- esp-hal/src/lib.rs | 4 ++-- esp-hal/src/mcpwm/operator.rs | 1 - esp-hal/src/prelude.rs | 2 +- esp-hal/src/uart.rs | 8 ++++---- examples/src/bin/adc.rs | 2 +- examples/src/bin/adc_cal.rs | 2 +- examples/src/bin/advanced_serial.rs | 2 +- examples/src/bin/blinky.rs | 2 +- examples/src/bin/blinky_erased_pins.rs | 2 +- examples/src/bin/dac.rs | 2 +- examples/src/bin/debug_assist.rs | 2 +- examples/src/bin/dma_extmem2mem.rs | 2 +- examples/src/bin/dma_mem2mem.rs | 2 +- examples/src/bin/embassy_hello_world.rs | 4 ++-- examples/src/bin/embassy_i2c.rs | 2 +- .../src/bin/embassy_i2c_bmp180_calibration_data.rs | 2 +- examples/src/bin/embassy_i2s_read.rs | 2 +- examples/src/bin/embassy_i2s_sound.rs | 2 +- examples/src/bin/embassy_multicore.rs | 3 +-- examples/src/bin/embassy_multicore_interrupt.rs | 2 +- examples/src/bin/embassy_multiprio.rs | 3 +-- examples/src/bin/embassy_parl_io_rx.rs | 2 +- examples/src/bin/embassy_parl_io_tx.rs | 2 +- examples/src/bin/embassy_rmt_rx.rs | 2 +- examples/src/bin/embassy_rmt_tx.rs | 2 +- examples/src/bin/embassy_serial.rs | 7 +++---- examples/src/bin/embassy_spi.rs | 2 +- examples/src/bin/embassy_touch.rs | 3 +-- examples/src/bin/embassy_twai.rs | 3 +-- examples/src/bin/embassy_usb_serial.rs | 9 ++++----- examples/src/bin/embassy_usb_serial_jtag.rs | 5 ++--- examples/src/bin/embassy_wait.rs | 3 +-- examples/src/bin/etm_blinky_systimer.rs | 2 +- examples/src/bin/etm_gpio.rs | 2 +- examples/src/bin/etm_timer.rs | 2 +- examples/src/bin/gpio_interrupt.rs | 2 +- examples/src/bin/hello_rgb.rs | 2 +- examples/src/bin/hello_world.rs | 2 +- examples/src/bin/hmac.rs | 2 +- examples/src/bin/i2c_bmp180_calibration_data.rs | 2 +- examples/src/bin/i2c_display.rs | 2 +- examples/src/bin/i2s_read.rs | 2 +- examples/src/bin/i2s_sound.rs | 2 +- examples/src/bin/ieee802154_receive_all_frames.rs | 6 +++--- examples/src/bin/ieee802154_receive_frame.rs | 6 +++--- examples/src/bin/ieee802154_send_broadcast_frame.rs | 6 +++--- examples/src/bin/ieee802154_send_frame.rs | 6 +++--- examples/src/bin/ieee802154_sniffer.rs | 6 +++--- examples/src/bin/lcd_cam_ov2640.rs | 2 +- examples/src/bin/lcd_i8080.rs | 6 +++--- examples/src/bin/ledc.rs | 2 +- examples/src/bin/lp_core_basic.rs | 2 +- examples/src/bin/lp_core_i2c.rs | 2 +- examples/src/bin/lp_core_uart.rs | 6 +++--- examples/src/bin/mcpwm.rs | 2 +- examples/src/bin/multicore.rs | 2 +- examples/src/bin/parl_io_rx.rs | 2 +- examples/src/bin/parl_io_tx.rs | 2 +- examples/src/bin/pcnt_encoder.rs | 2 +- examples/src/bin/psram_octal.rs | 2 +- examples/src/bin/psram_quad.rs | 2 +- examples/src/bin/qspi_flash.rs | 2 +- examples/src/bin/ram.rs | 2 +- examples/src/bin/rmt_rx.rs | 2 +- examples/src/bin/rmt_tx.rs | 2 +- examples/src/bin/rng.rs | 2 +- examples/src/bin/rtc_time.rs | 2 +- examples/src/bin/rtc_watchdog.rs | 2 +- examples/src/bin/serial_interrupts.rs | 6 +++--- examples/src/bin/sleep_timer.rs | 3 +-- examples/src/bin/sleep_timer_ext0.rs | 3 +-- examples/src/bin/sleep_timer_ext1.rs | 3 +-- examples/src/bin/sleep_timer_lpio.rs | 3 +-- examples/src/bin/sleep_timer_rtcio.rs | 3 +-- examples/src/bin/software_interrupts.rs | 2 +- .../src/bin/spi_halfduplex_read_manufacturer_id.rs | 2 +- examples/src/bin/spi_loopback.rs | 2 +- examples/src/bin/spi_loopback_dma.rs | 2 +- examples/src/bin/spi_slave_dma.rs | 2 +- examples/src/bin/systimer.rs | 2 +- examples/src/bin/timer_interrupt.rs | 2 +- examples/src/bin/touch.rs | 2 +- examples/src/bin/twai.rs | 2 +- examples/src/bin/ulp_riscv_core_basic.rs | 2 +- examples/src/bin/usb_serial.rs | 2 +- examples/src/bin/usb_serial_jtag.rs | 2 +- examples/src/bin/watchdog.rs | 2 +- examples/src/bin/wifi_80211_tx.rs | 2 +- examples/src/bin/wifi_access_point.rs | 2 +- examples/src/bin/wifi_access_point_with_sta.rs | 2 +- examples/src/bin/wifi_bench.rs | 2 +- examples/src/bin/wifi_ble.rs | 2 +- examples/src/bin/wifi_coex.rs | 2 +- examples/src/bin/wifi_dhcp.rs | 2 +- examples/src/bin/wifi_embassy_access_point.rs | 2 +- .../src/bin/wifi_embassy_access_point_with_sta.rs | 2 +- examples/src/bin/wifi_embassy_bench.rs | 2 +- examples/src/bin/wifi_embassy_ble.rs | 2 +- examples/src/bin/wifi_embassy_dhcp.rs | 2 +- examples/src/bin/wifi_embassy_esp_now.rs | 2 +- examples/src/bin/wifi_embassy_esp_now_duplex.rs | 2 +- examples/src/bin/wifi_esp_now.rs | 2 +- examples/src/bin/wifi_sniffer.rs | 2 +- examples/src/bin/wifi_static_ip.rs | 2 +- hil-test/tests/aes.rs | 2 +- hil-test/tests/aes_dma.rs | 2 +- hil-test/tests/clock_monitor.rs | 4 ++-- hil-test/tests/delay.rs | 4 ++-- hil-test/tests/dma_mem2mem.rs | 3 +-- hil-test/tests/ecc.rs | 2 +- hil-test/tests/embassy_interrupt_executor.rs | 3 +-- hil-test/tests/embassy_timers_executors.rs | 2 +- hil-test/tests/get_time.rs | 4 ++-- hil-test/tests/gpio.rs | 7 +++---- hil-test/tests/i2s.rs | 2 +- hil-test/tests/i2s_async.rs | 2 +- hil-test/tests/interrupt.rs | 2 +- hil-test/tests/lcd_cam_i8080.rs | 8 ++++---- hil-test/tests/lcd_cam_i8080_async.rs | 11 ++++------- hil-test/tests/pcnt.rs | 3 +-- hil-test/tests/qspi_read.rs | 8 ++------ hil-test/tests/qspi_write.rs | 8 ++------ hil-test/tests/qspi_write_read.rs | 8 ++------ hil-test/tests/rmt.rs | 2 +- hil-test/tests/rsa.rs | 2 +- hil-test/tests/sha.rs | 4 ++-- hil-test/tests/spi_full_duplex.rs | 2 +- hil-test/tests/spi_full_duplex_dma.rs | 4 +--- hil-test/tests/spi_full_duplex_dma_async.rs | 2 +- hil-test/tests/spi_full_duplex_dma_pcnt.rs | 2 +- hil-test/tests/spi_half_duplex_read.rs | 2 +- hil-test/tests/spi_half_duplex_write.rs | 2 +- hil-test/tests/systimer.rs | 2 +- hil-test/tests/twai.rs | 2 +- hil-test/tests/uart.rs | 2 +- hil-test/tests/uart_async.rs | 4 ++-- hil-test/tests/uart_tx_rx.rs | 2 +- hil-test/tests/uart_tx_rx_async.rs | 3 +-- hil-test/tests/usb_serial_jtag.rs | 4 ++-- 142 files changed, 188 insertions(+), 224 deletions(-) diff --git a/esp-hal/MIGRATING-0.20.md b/esp-hal/MIGRATING-0.20.md index d0eec4a8881..0714b5a81e6 100644 --- a/esp-hal/MIGRATING-0.20.md +++ b/esp-hal/MIGRATING-0.20.md @@ -19,7 +19,7 @@ Instead of manually grabbing peripherals and setting up clocks, you should now c - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); -+ let (peripherals, clocks) = esp_hal::init(Config::default()); ++ let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); // ... } diff --git a/esp-hal/src/clock/mod.rs b/esp-hal/src/clock/mod.rs index 100d95454dd..59cb01cf6a1 100644 --- a/esp-hal/src/clock/mod.rs +++ b/esp-hal/src/clock/mod.rs @@ -49,14 +49,14 @@ //! # fn main() { //! // Initialize with the highest possible frequency for this chip //! let (peripherals, clocks) = esp_hal::init({ -//! let mut config = Config::default(); +//! let mut config = esp_hal::Config::default(); //! config.cpu_clock = CpuClock::max(); //! config //! }); //! //! // Initialize with custom clock frequency //! // let (peripherals, clocks) = esp_hal::init({ -//! // let mut config = Config::default(); +//! // let mut config = esp_hal::Config::default(); #![cfg_attr( not(any(esp32c2, esp32h2)), doc = "// config.cpu_clock = CpuClock::Clock160MHz;" @@ -67,7 +67,7 @@ //! // }); //! // //! // Initialize with default clock frequency for this chip -//! // let (peripherals, clocks) = esp_hal::init(Config::default()); +//! // let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); //! # } //! ``` diff --git a/esp-hal/src/lcd_cam/lcd/i8080.rs b/esp-hal/src/lcd_cam/lcd/i8080.rs index 694d73b723c..27af36a8578 100644 --- a/esp-hal/src/lcd_cam/lcd/i8080.rs +++ b/esp-hal/src/lcd_cam/lcd/i8080.rs @@ -16,7 +16,7 @@ //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::gpio::Io; -//! # use esp_hal::lcd_cam::{LcdCam, lcd::i8080::{self, I8080, TxEightBits}}; +//! # use esp_hal::lcd_cam::{LcdCam, lcd::i8080::{Config, I8080, TxEightBits}}; //! # use esp_hal::dma_buffers; //! # use esp_hal::dma::{Dma, DmaPriority}; //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); @@ -49,7 +49,7 @@ //! tx_descriptors, //! tx_pins, //! 20.MHz(), -//! i8080::Config::default(), +//! Config::default(), //! &clocks, //! ) //! .with_ctrl_pins(io.pins.gpio0, io.pins.gpio47); diff --git a/esp-hal/src/lib.rs b/esp-hal/src/lib.rs index 9b98ac3e546..07636b5cfb9 100644 --- a/esp-hal/src/lib.rs +++ b/esp-hal/src/lib.rs @@ -73,7 +73,7 @@ //! //! #[entry] //! fn main() -> ! { -//! let (peripherals, clocks) = esp_hal::init(Config::default()); +//! let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); //! //! // Set GPIO0 as an output, and set its state high initially. //! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); @@ -625,7 +625,7 @@ macro_rules! before_snippet { # loop {} # } # fn main() { -# let (peripherals, clocks) = esp_hal::init(Config::default()); +# let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); "# }; } diff --git a/esp-hal/src/mcpwm/operator.rs b/esp-hal/src/mcpwm/operator.rs index 2f73324e7ac..9d08ac1966a 100644 --- a/esp-hal/src/mcpwm/operator.rs +++ b/esp-hal/src/mcpwm/operator.rs @@ -486,7 +486,6 @@ impl<'d, Pin: OutputPin, PWM: PwmPeripheral, const OP: u8, const IS_A: bool> /// # use esp_hal::mcpwm::{McPwm, PeripheralClockConfig}; /// # use esp_hal::mcpwm::operator::{DeadTimeCfg, PwmPinConfig, PWMStream}; /// # use esp_hal::gpio::Io; -/// let (peripherals, clocks) = esp_hal::init(Config::default()); /// # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); /// // active high complementary using PWMA input /// let bridge_active = DeadTimeCfg::new_ahc(); diff --git a/esp-hal/src/prelude.rs b/esp-hal/src/prelude.rs index a6cbed5434d..11ad6b9ae56 100644 --- a/esp-hal/src/prelude.rs +++ b/esp-hal/src/prelude.rs @@ -38,4 +38,4 @@ pub use crate::timer::timg::{ pub use crate::timer::Timer as _esp_hal_timer_Timer; #[cfg(any(uart0, uart1, uart2))] pub use crate::uart::Instance as _esp_hal_uart_Instance; -pub use crate::{clock::CpuClock, entry, macros::*, Config, InterruptConfigurable}; +pub use crate::{clock::CpuClock, entry, macros::*, InterruptConfigurable}; diff --git a/esp-hal/src/uart.rs b/esp-hal/src/uart.rs index c76756112ed..62e49a474e1 100644 --- a/esp-hal/src/uart.rs +++ b/esp-hal/src/uart.rs @@ -56,12 +56,12 @@ //! ### Sending and Receiving Data //! ```rust, no_run #![doc = crate::before_snippet!()] -//! # use esp_hal::uart::{self, Uart}; +//! # use esp_hal::uart::{config::Config, Uart}; //! # use esp_hal::gpio::Io; //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut uart1 = Uart::new_with_config( //! # peripherals.UART1, -//! # uart::config::Config::default(), +//! # Config::default(), //! # &clocks, //! # io.pins.gpio1, //! # io.pins.gpio2, @@ -74,12 +74,12 @@ //! ### Splitting the UART into TX and RX Components //! ```rust, no_run #![doc = crate::before_snippet!()] -//! # use esp_hal::uart::{self, Uart}; +//! # use esp_hal::uart::{config::Config, Uart}; //! # use esp_hal::gpio::Io; //! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); //! # let mut uart1 = Uart::new_with_config( //! # peripherals.UART1, -//! # uart::config::Config::default(), +//! # Config::default(), //! # &clocks, //! # io.pins.gpio1, //! # io.pins.gpio2, diff --git a/examples/src/bin/adc.rs b/examples/src/bin/adc.rs index ab11bb5e89e..1c9413e2c26 100644 --- a/examples/src/bin/adc.rs +++ b/examples/src/bin/adc.rs @@ -27,7 +27,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/adc_cal.rs b/examples/src/bin/adc_cal.rs index d1d667a4c35..1466e01cc46 100644 --- a/examples/src/bin/adc_cal.rs +++ b/examples/src/bin/adc_cal.rs @@ -23,7 +23,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/advanced_serial.rs b/examples/src/bin/advanced_serial.rs index d41bf15d288..b4a3760189f 100644 --- a/examples/src/bin/advanced_serial.rs +++ b/examples/src/bin/advanced_serial.rs @@ -19,7 +19,7 @@ use nb::block; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/blinky.rs b/examples/src/bin/blinky.rs index fc592c4f535..114854599eb 100644 --- a/examples/src/bin/blinky.rs +++ b/examples/src/bin/blinky.rs @@ -17,7 +17,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); // Set GPIO0 as an output, and set its state high initially. let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/blinky_erased_pins.rs b/examples/src/bin/blinky_erased_pins.rs index 435601cbc2c..65204583333 100644 --- a/examples/src/bin/blinky_erased_pins.rs +++ b/examples/src/bin/blinky_erased_pins.rs @@ -20,7 +20,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/dac.rs b/examples/src/bin/dac.rs index b379a9b3bd9..825600c09a5 100644 --- a/examples/src/bin/dac.rs +++ b/examples/src/bin/dac.rs @@ -23,7 +23,7 @@ use esp_hal::{analog::dac::Dac, delay::Delay, gpio::Io, prelude::*}; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/debug_assist.rs b/examples/src/bin/debug_assist.rs index 1599a77f67d..3a39b30cb7e 100644 --- a/examples/src/bin/debug_assist.rs +++ b/examples/src/bin/debug_assist.rs @@ -18,7 +18,7 @@ static DA: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); let mut da = DebugAssist::new(peripherals.ASSIST_DEBUG); da.set_interrupt_handler(interrupt_handler); diff --git a/examples/src/bin/dma_extmem2mem.rs b/examples/src/bin/dma_extmem2mem.rs index a6ff9a09963..fcc4832b93a 100644 --- a/examples/src/bin/dma_extmem2mem.rs +++ b/examples/src/bin/dma_extmem2mem.rs @@ -62,7 +62,7 @@ fn init_heap(psram: impl esp_hal::peripheral::Peripheral

! { esp_println::logger::init_logger(log::LevelFilter::Info); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); init_heap(peripherals.PSRAM); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/dma_mem2mem.rs b/examples/src/bin/dma_mem2mem.rs index 5c153ecbfb4..39f7a02f434 100644 --- a/examples/src/bin/dma_mem2mem.rs +++ b/examples/src/bin/dma_mem2mem.rs @@ -21,7 +21,7 @@ const DATA_SIZE: usize = 1024 * 10; fn main() -> ! { esp_println::logger::init_logger(log::LevelFilter::Info); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/embassy_hello_world.rs b/examples/src/bin/embassy_hello_world.rs index 6e2b4a10079..9b47ccf416c 100644 --- a/examples/src/bin/embassy_hello_world.rs +++ b/examples/src/bin/embassy_hello_world.rs @@ -12,7 +12,7 @@ use embassy_executor::Spawner; use embassy_time::{Duration, Timer}; use esp_backtrace as _; -use esp_hal::{prelude::*, timer::timg::TimerGroup}; +use esp_hal::timer::timg::TimerGroup; #[embassy_executor::task] async fn run() { @@ -25,7 +25,7 @@ async fn run() { #[esp_hal_embassy::main] async fn main(spawner: Spawner) { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); esp_println::println!("Init!"); diff --git a/examples/src/bin/embassy_i2c.rs b/examples/src/bin/embassy_i2c.rs index f5ff82fa146..995c99942ad 100644 --- a/examples/src/bin/embassy_i2c.rs +++ b/examples/src/bin/embassy_i2c.rs @@ -24,7 +24,7 @@ use lis3dh_async::{Lis3dh, Range, SlaveAddr}; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs b/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs index e30d08eec9e..2ba39581c2d 100644 --- a/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs +++ b/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs @@ -24,7 +24,7 @@ use esp_hal::{gpio::Io, i2c::I2C, prelude::*, timer::timg::TimerGroup}; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_i2s_read.rs b/examples/src/bin/embassy_i2s_read.rs index ac2f549840e..24324c64661 100644 --- a/examples/src/bin/embassy_i2s_read.rs +++ b/examples/src/bin/embassy_i2s_read.rs @@ -32,7 +32,7 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { println!("Init!"); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_i2s_sound.rs b/examples/src/bin/embassy_i2s_sound.rs index 29320016823..1a5a0a76b02 100644 --- a/examples/src/bin/embassy_i2s_sound.rs +++ b/examples/src/bin/embassy_i2s_sound.rs @@ -54,7 +54,7 @@ const SINE: [i16; 64] = [ #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { println!("Init!"); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_multicore.rs b/examples/src/bin/embassy_multicore.rs index 578a4907f25..872d0846e3d 100644 --- a/examples/src/bin/embassy_multicore.rs +++ b/examples/src/bin/embassy_multicore.rs @@ -22,7 +22,6 @@ use esp_hal::{ cpu_control::{CpuControl, Stack}, get_core, gpio::{AnyOutput, Io, Level}, - prelude::*, timer::{timg::TimerGroup, ErasedTimer}, }; use esp_hal_embassy::Executor; @@ -52,7 +51,7 @@ async fn control_led( #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/embassy_multicore_interrupt.rs b/examples/src/bin/embassy_multicore_interrupt.rs index 82ae89188a0..48c72e8e894 100644 --- a/examples/src/bin/embassy_multicore_interrupt.rs +++ b/examples/src/bin/embassy_multicore_interrupt.rs @@ -71,7 +71,7 @@ async fn enable_disable_led(control: &'static Signal ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); diff --git a/examples/src/bin/embassy_multiprio.rs b/examples/src/bin/embassy_multiprio.rs index 56ddc0e7ca7..d6f52df36d2 100644 --- a/examples/src/bin/embassy_multiprio.rs +++ b/examples/src/bin/embassy_multiprio.rs @@ -25,7 +25,6 @@ use embassy_time::{Duration, Instant, Ticker, Timer}; use esp_backtrace as _; use esp_hal::{ interrupt::{software::SoftwareInterruptControl, Priority}, - prelude::*, timer::{timg::TimerGroup, ErasedTimer}, }; use esp_hal_embassy::InterruptExecutor; @@ -72,7 +71,7 @@ async fn main(low_prio_spawner: Spawner) { esp_println::logger::init_logger_from_env(); println!("Init!"); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); diff --git a/examples/src/bin/embassy_parl_io_rx.rs b/examples/src/bin/embassy_parl_io_rx.rs index 240605be205..dae767bbd47 100644 --- a/examples/src/bin/embassy_parl_io_rx.rs +++ b/examples/src/bin/embassy_parl_io_rx.rs @@ -26,7 +26,7 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let systimer = SystemTimer::new(peripherals.SYSTIMER).split::(); esp_hal_embassy::init(&clocks, systimer.alarm0); diff --git a/examples/src/bin/embassy_parl_io_tx.rs b/examples/src/bin/embassy_parl_io_tx.rs index ba88313e9f7..7a90821e50f 100644 --- a/examples/src/bin/embassy_parl_io_tx.rs +++ b/examples/src/bin/embassy_parl_io_tx.rs @@ -37,7 +37,7 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let systimer = SystemTimer::new(peripherals.SYSTIMER).split::(); esp_hal_embassy::init(&clocks, systimer.alarm0); diff --git a/examples/src/bin/embassy_rmt_rx.rs b/examples/src/bin/embassy_rmt_rx.rs index 06c82453713..794aeceedd9 100644 --- a/examples/src/bin/embassy_rmt_rx.rs +++ b/examples/src/bin/embassy_rmt_rx.rs @@ -39,7 +39,7 @@ async fn signal_task(mut pin: Output<'static, Gpio5>) { #[esp_hal_embassy::main] async fn main(spawner: Spawner) { println!("Init!"); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_rmt_tx.rs b/examples/src/bin/embassy_rmt_tx.rs index 8eed5f6c971..c8cc3c83427 100644 --- a/examples/src/bin/embassy_rmt_tx.rs +++ b/examples/src/bin/embassy_rmt_tx.rs @@ -25,7 +25,7 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { println!("Init!"); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_serial.rs b/examples/src/bin/embassy_serial.rs index b923f384f1b..541ea6c8e89 100644 --- a/examples/src/bin/embassy_serial.rs +++ b/examples/src/bin/embassy_serial.rs @@ -15,10 +15,9 @@ use esp_backtrace as _; use esp_hal::{ gpio::Io, peripherals::UART0, - prelude::*, timer::timg::TimerGroup, uart::{ - config::{AtCmdConfig, Config as UartConfig}, + config::{AtCmdConfig, Config}, Uart, UartRx, UartTx, @@ -79,7 +78,7 @@ async fn reader( #[esp_hal_embassy::main] async fn main(spawner: Spawner) { esp_println::println!("Init!"); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); @@ -103,7 +102,7 @@ async fn main(spawner: Spawner) { } } - let config = UartConfig::default().rx_fifo_full_threshold(READ_BUF_SIZE as u16); + let config = Config::default().rx_fifo_full_threshold(READ_BUF_SIZE as u16); let mut uart0 = Uart::new_async_with_config(peripherals.UART0, config, &clocks, tx_pin, rx_pin).unwrap(); diff --git a/examples/src/bin/embassy_spi.rs b/examples/src/bin/embassy_spi.rs index ee06bbb7ab3..a8f6ab68720 100644 --- a/examples/src/bin/embassy_spi.rs +++ b/examples/src/bin/embassy_spi.rs @@ -33,7 +33,7 @@ use esp_hal::{ #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_touch.rs b/examples/src/bin/embassy_touch.rs index 190bfda1927..e0f199442f9 100644 --- a/examples/src/bin/embassy_touch.rs +++ b/examples/src/bin/embassy_touch.rs @@ -18,7 +18,6 @@ use embassy_time::{Duration, Timer}; use esp_backtrace as _; use esp_hal::{ gpio::Io, - prelude::*, rtc_cntl::Rtc, timer::timg::TimerGroup, touch::{Touch, TouchConfig, TouchPad}, @@ -28,7 +27,7 @@ use esp_println::println; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_twai.rs b/examples/src/bin/embassy_twai.rs index e61e47c4080..10ddc4e8df9 100644 --- a/examples/src/bin/embassy_twai.rs +++ b/examples/src/bin/embassy_twai.rs @@ -28,7 +28,6 @@ use esp_hal::{ gpio::Io, interrupt, peripherals::{self, TWAI0}, - prelude::*, timer::timg::TimerGroup, twai::{self, EspTwaiFrame, TwaiMode, TwaiRx, TwaiTx}, }; @@ -83,7 +82,7 @@ async fn transmitter( #[esp_hal_embassy::main] async fn main(spawner: Spawner) { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_usb_serial.rs b/examples/src/bin/embassy_usb_serial.rs index 422b43b258d..f9acd516163 100644 --- a/examples/src/bin/embassy_usb_serial.rs +++ b/examples/src/bin/embassy_usb_serial.rs @@ -23,17 +23,16 @@ use esp_backtrace as _; use esp_hal::{ gpio::Io, otg_fs::{ - asynch::{Config as OtgConfig, Driver}, + asynch::{Config, Driver}, Usb, }, - prelude::*, timer::timg::TimerGroup, }; #[esp_hal_embassy::main] -async fn main(_spawner: Spawner) -> () { +async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); @@ -44,7 +43,7 @@ async fn main(_spawner: Spawner) -> () { // Create the driver, from the HAL. let mut ep_out_buffer = [0u8; 1024]; - let config = OtgConfig::default(); + let config = Config::default(); let driver = Driver::new(usb, &mut ep_out_buffer, config); diff --git a/examples/src/bin/embassy_usb_serial_jtag.rs b/examples/src/bin/embassy_usb_serial_jtag.rs index 293a1b3d317..d72089fdfb5 100644 --- a/examples/src/bin/embassy_usb_serial_jtag.rs +++ b/examples/src/bin/embassy_usb_serial_jtag.rs @@ -12,7 +12,6 @@ use embassy_executor::Spawner; use embassy_sync::{blocking_mutex::raw::NoopRawMutex, signal::Signal}; use esp_backtrace as _; use esp_hal::{ - prelude::*, timer::timg::TimerGroup, usb_serial_jtag::{UsbSerialJtag, UsbSerialJtagRx, UsbSerialJtagTx}, Async, @@ -62,9 +61,9 @@ async fn reader( } #[esp_hal_embassy::main] -async fn main(spawner: Spawner) -> () { +async fn main(spawner: Spawner) { esp_println::println!("Init!"); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/embassy_wait.rs b/examples/src/bin/embassy_wait.rs index 86d69ceeab3..9b9d5854db7 100644 --- a/examples/src/bin/embassy_wait.rs +++ b/examples/src/bin/embassy_wait.rs @@ -13,14 +13,13 @@ use embassy_time::{Duration, Timer}; use esp_backtrace as _; use esp_hal::{ gpio::{Input, Io, Pull}, - prelude::*, timer::timg::TimerGroup, }; #[esp_hal_embassy::main] async fn main(_spawner: Spawner) { esp_println::println!("Init!"); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/examples/src/bin/etm_blinky_systimer.rs b/examples/src/bin/etm_blinky_systimer.rs index 97432cbdb8f..b0057d4cee5 100644 --- a/examples/src/bin/etm_blinky_systimer.rs +++ b/examples/src/bin/etm_blinky_systimer.rs @@ -24,7 +24,7 @@ use fugit::ExtU32; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); let syst = SystemTimer::new(peripherals.SYSTIMER); let syst_alarms = syst.split::(); diff --git a/examples/src/bin/etm_gpio.rs b/examples/src/bin/etm_gpio.rs index b470e6f054c..36adfbdc393 100644 --- a/examples/src/bin/etm_gpio.rs +++ b/examples/src/bin/etm_gpio.rs @@ -22,7 +22,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let mut led = io.pins.gpio1; diff --git a/examples/src/bin/etm_timer.rs b/examples/src/bin/etm_timer.rs index 07b3ef571f9..649e64590cc 100644 --- a/examples/src/bin/etm_timer.rs +++ b/examples/src/bin/etm_timer.rs @@ -28,7 +28,7 @@ static TIMER0: Mutex, esp_hal::Blocking>>>> = #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); let timer0 = timg0.timer0; diff --git a/examples/src/bin/gpio_interrupt.rs b/examples/src/bin/gpio_interrupt.rs index 2082353458a..2e7a60fe36c 100644 --- a/examples/src/bin/gpio_interrupt.rs +++ b/examples/src/bin/gpio_interrupt.rs @@ -32,7 +32,7 @@ cfg_if::cfg_if! { #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); // Set GPIO2 as an output, and set its state high initially. let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/hello_rgb.rs b/examples/src/bin/hello_rgb.rs index fbc9a937032..d2afd555892 100644 --- a/examples/src/bin/hello_rgb.rs +++ b/examples/src/bin/hello_rgb.rs @@ -36,7 +36,7 @@ use smart_leds::{ #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/hello_world.rs b/examples/src/bin/hello_world.rs index 18728385f7b..ebda656f449 100644 --- a/examples/src/bin/hello_world.rs +++ b/examples/src/bin/hello_world.rs @@ -19,7 +19,7 @@ use esp_hal::{delay::Delay, gpio::Io, prelude::*, uart::Uart}; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/hmac.rs b/examples/src/bin/hmac.rs index 7c5adf1ffdf..0cd9bf634c2 100644 --- a/examples/src/bin/hmac.rs +++ b/examples/src/bin/hmac.rs @@ -73,7 +73,7 @@ type HmacSha256 = HmacSw; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); let mut rng = Rng::new(peripherals.RNG); diff --git a/examples/src/bin/i2c_bmp180_calibration_data.rs b/examples/src/bin/i2c_bmp180_calibration_data.rs index cd6fd36ee15..e3f61626a01 100644 --- a/examples/src/bin/i2c_bmp180_calibration_data.rs +++ b/examples/src/bin/i2c_bmp180_calibration_data.rs @@ -17,7 +17,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/i2c_display.rs b/examples/src/bin/i2c_display.rs index 48caa04f6fc..a225d44b0f4 100644 --- a/examples/src/bin/i2c_display.rs +++ b/examples/src/bin/i2c_display.rs @@ -28,7 +28,7 @@ use ssd1306::{prelude::*, I2CDisplayInterface, Ssd1306}; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let delay = Delay::new(&clocks); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/i2s_read.rs b/examples/src/bin/i2s_read.rs index e4b926f2191..5a1616eef38 100644 --- a/examples/src/bin/i2s_read.rs +++ b/examples/src/bin/i2s_read.rs @@ -28,7 +28,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/i2s_sound.rs b/examples/src/bin/i2s_sound.rs index 4fe2b5894c0..998bb127cdf 100644 --- a/examples/src/bin/i2s_sound.rs +++ b/examples/src/bin/i2s_sound.rs @@ -49,7 +49,7 @@ const SINE: [i16; 64] = [ #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/ieee802154_receive_all_frames.rs b/examples/src/bin/ieee802154_receive_all_frames.rs index f623dec8b2d..ce078a0223d 100644 --- a/examples/src/bin/ieee802154_receive_all_frames.rs +++ b/examples/src/bin/ieee802154_receive_all_frames.rs @@ -5,15 +5,15 @@ use esp_backtrace as _; use esp_hal::prelude::*; -use esp_ieee802154::{Config as Ieee802154Config, Ieee802154}; +use esp_ieee802154::{Config, Ieee802154}; use esp_println::println; #[entry] fn main() -> ! { - let (mut peripherals, _clocks) = esp_hal::init(Config::default()); + let (mut peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); let mut ieee802154 = Ieee802154::new(peripherals.IEEE802154, &mut peripherals.RADIO_CLK); - ieee802154.set_config(Ieee802154Config { + ieee802154.set_config(Config { channel: 15, promiscuous: true, rx_when_idle: true, diff --git a/examples/src/bin/ieee802154_receive_frame.rs b/examples/src/bin/ieee802154_receive_frame.rs index 19ed94219d5..5fa678a3a52 100644 --- a/examples/src/bin/ieee802154_receive_frame.rs +++ b/examples/src/bin/ieee802154_receive_frame.rs @@ -5,15 +5,15 @@ use esp_backtrace as _; use esp_hal::prelude::*; -use esp_ieee802154::{Config as Ieee802154Config, Ieee802154}; +use esp_ieee802154::{Config, Ieee802154}; use esp_println::println; #[entry] fn main() -> ! { - let (mut peripherals, _clocks) = esp_hal::init(Config::default()); + let (mut peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); let mut ieee802154 = Ieee802154::new(peripherals.IEEE802154, &mut peripherals.RADIO_CLK); - ieee802154.set_config(Ieee802154Config { + ieee802154.set_config(Config { channel: 15, promiscuous: false, rx_when_idle: true, diff --git a/examples/src/bin/ieee802154_send_broadcast_frame.rs b/examples/src/bin/ieee802154_send_broadcast_frame.rs index 3ee1f554862..1053a934e16 100644 --- a/examples/src/bin/ieee802154_send_broadcast_frame.rs +++ b/examples/src/bin/ieee802154_send_broadcast_frame.rs @@ -5,7 +5,7 @@ use esp_backtrace as _; use esp_hal::{delay::Delay, prelude::*}; -use esp_ieee802154::{Config as Ieee802154Config, Frame, Ieee802154}; +use esp_ieee802154::{Config, Frame, Ieee802154}; use esp_println::println; use ieee802154::mac::{ Address, @@ -19,13 +19,13 @@ use ieee802154::mac::{ #[entry] fn main() -> ! { - let (mut peripherals, clocks) = esp_hal::init(Config::default()); + let (mut peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let delay = Delay::new(&clocks); let mut ieee802154 = Ieee802154::new(peripherals.IEEE802154, &mut peripherals.RADIO_CLK); - ieee802154.set_config(Ieee802154Config { + ieee802154.set_config(Config { channel: 15, promiscuous: false, pan_id: Some(0x4242), diff --git a/examples/src/bin/ieee802154_send_frame.rs b/examples/src/bin/ieee802154_send_frame.rs index 944688784a7..9cf2e72ba9e 100644 --- a/examples/src/bin/ieee802154_send_frame.rs +++ b/examples/src/bin/ieee802154_send_frame.rs @@ -5,7 +5,7 @@ use esp_backtrace as _; use esp_hal::{delay::Delay, prelude::*}; -use esp_ieee802154::{Config as Ieee802154Config, Frame, Ieee802154}; +use esp_ieee802154::{Config, Frame, Ieee802154}; use esp_println::println; use ieee802154::mac::{ Address, @@ -19,13 +19,13 @@ use ieee802154::mac::{ #[entry] fn main() -> ! { - let (mut peripherals, clocks) = esp_hal::init(Config::default()); + let (mut peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let delay = Delay::new(&clocks); let mut ieee802154 = Ieee802154::new(peripherals.IEEE802154, &mut peripherals.RADIO_CLK); - ieee802154.set_config(Ieee802154Config { + ieee802154.set_config(Config { channel: 15, promiscuous: false, pan_id: Some(0x4242), diff --git a/examples/src/bin/ieee802154_sniffer.rs b/examples/src/bin/ieee802154_sniffer.rs index 68e2e98c7f5..c78a7166a1e 100644 --- a/examples/src/bin/ieee802154_sniffer.rs +++ b/examples/src/bin/ieee802154_sniffer.rs @@ -9,12 +9,12 @@ use esp_backtrace as _; use esp_hal::{gpio::Io, prelude::*, reset::software_reset, uart::Uart}; -use esp_ieee802154::{Config as Ieee802154Config, Ieee802154}; +use esp_ieee802154::{Config, Ieee802154}; use esp_println::println; #[entry] fn main() -> ! { - let (mut peripherals, clocks) = esp_hal::init(Config::default()); + let (mut peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); @@ -53,7 +53,7 @@ fn main() -> ! { let radio = peripherals.IEEE802154; let mut ieee802154 = Ieee802154::new(radio, &mut peripherals.RADIO_CLK); - ieee802154.set_config(Ieee802154Config { + ieee802154.set_config(Config { channel, promiscuous: true, rx_when_idle: true, diff --git a/examples/src/bin/lcd_cam_ov2640.rs b/examples/src/bin/lcd_cam_ov2640.rs index 1ff4d9486b0..caa62eeb383 100644 --- a/examples/src/bin/lcd_cam_ov2640.rs +++ b/examples/src/bin/lcd_cam_ov2640.rs @@ -42,7 +42,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/lcd_i8080.rs b/examples/src/bin/lcd_i8080.rs index 6bcce17e26c..20597d7babb 100644 --- a/examples/src/bin/lcd_i8080.rs +++ b/examples/src/bin/lcd_i8080.rs @@ -28,7 +28,7 @@ use esp_hal::{ dma_buffers, gpio::{Io, Level, Output}, lcd_cam::{ - lcd::i8080::{self, TxEightBits, I8080}, + lcd::i8080::{Config, TxEightBits, I8080}, LcdCam, }, prelude::*, @@ -37,7 +37,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); @@ -77,7 +77,7 @@ fn main() -> ! { tx_descriptors, tx_pins, 20.MHz(), - i8080::Config::default(), + Config::default(), &clocks, ) .with_ctrl_pins(lcd_rs, lcd_wr); diff --git a/examples/src/bin/ledc.rs b/examples/src/bin/ledc.rs index 4b1a2d43702..b7dd70e6c20 100644 --- a/examples/src/bin/ledc.rs +++ b/examples/src/bin/ledc.rs @@ -24,7 +24,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let led = io.pins.gpio0; diff --git a/examples/src/bin/lp_core_basic.rs b/examples/src/bin/lp_core_basic.rs index a868158cdb8..9b35e8c0eba 100644 --- a/examples/src/bin/lp_core_basic.rs +++ b/examples/src/bin/lp_core_basic.rs @@ -23,7 +23,7 @@ use esp_println::{print, println}; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); // configure GPIO 1 as LP output pin let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/lp_core_i2c.rs b/examples/src/bin/lp_core_i2c.rs index 4f21a5b70b7..c4a817fd9f4 100644 --- a/examples/src/bin/lp_core_i2c.rs +++ b/examples/src/bin/lp_core_i2c.rs @@ -25,7 +25,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/lp_core_uart.rs b/examples/src/bin/lp_core_uart.rs index 6296c9813d7..79e5962e946 100644 --- a/examples/src/bin/lp_core_uart.rs +++ b/examples/src/bin/lp_core_uart.rs @@ -22,13 +22,13 @@ use esp_hal::{ }, lp_core::{LpCore, LpCoreWakeupSource}, prelude::*, - uart::{config::Config as UartConfig, lp_uart::LpUart, Uart}, + uart::{config::Config, lp_uart::LpUart, Uart}, }; use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); @@ -36,7 +36,7 @@ fn main() -> ! { let mut uart1 = Uart::new_with_config( peripherals.UART1, - UartConfig::default(), + Config::default(), &clocks, io.pins.gpio6, io.pins.gpio7, diff --git a/examples/src/bin/mcpwm.rs b/examples/src/bin/mcpwm.rs index 0e072159983..783046ae783 100644 --- a/examples/src/bin/mcpwm.rs +++ b/examples/src/bin/mcpwm.rs @@ -18,7 +18,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let pin = io.pins.gpio0; diff --git a/examples/src/bin/multicore.rs b/examples/src/bin/multicore.rs index aeb57e05075..28297e91733 100644 --- a/examples/src/bin/multicore.rs +++ b/examples/src/bin/multicore.rs @@ -23,7 +23,7 @@ static mut APP_CORE_STACK: Stack<8192> = Stack::new(); #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/parl_io_rx.rs b/examples/src/bin/parl_io_rx.rs index ea3f163bcd2..04d31ce6302 100644 --- a/examples/src/bin/parl_io_rx.rs +++ b/examples/src/bin/parl_io_rx.rs @@ -22,7 +22,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/parl_io_tx.rs b/examples/src/bin/parl_io_tx.rs index 8f0bc12bbdc..8fc1b9eac6d 100644 --- a/examples/src/bin/parl_io_tx.rs +++ b/examples/src/bin/parl_io_tx.rs @@ -33,7 +33,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/pcnt_encoder.rs b/examples/src/bin/pcnt_encoder.rs index eb40c7f7d8e..5cba71d117a 100644 --- a/examples/src/bin/pcnt_encoder.rs +++ b/examples/src/bin/pcnt_encoder.rs @@ -37,7 +37,7 @@ static VALUE: AtomicI32 = AtomicI32::new(0); #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/psram_octal.rs b/examples/src/bin/psram_octal.rs index dad49894939..a1c46c7d80f 100644 --- a/examples/src/bin/psram_octal.rs +++ b/examples/src/bin/psram_octal.rs @@ -30,7 +30,7 @@ fn main() -> ! { #[cfg(debug_assertions)] compile_error!("This example MUST be built in release mode!"); - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); psram::init_psram(peripherals.PSRAM); init_psram_heap(); diff --git a/examples/src/bin/psram_quad.rs b/examples/src/bin/psram_quad.rs index cf11cbc87da..93c0d9747ac 100644 --- a/examples/src/bin/psram_quad.rs +++ b/examples/src/bin/psram_quad.rs @@ -30,7 +30,7 @@ fn main() -> ! { #[cfg(debug_assertions)] compile_error!("PSRAM example must be built in release mode!"); - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); psram::init_psram(peripherals.PSRAM); init_psram_heap(); diff --git a/examples/src/bin/qspi_flash.rs b/examples/src/bin/qspi_flash.rs index 169d7853dc0..65ee4ef5732 100644 --- a/examples/src/bin/qspi_flash.rs +++ b/examples/src/bin/qspi_flash.rs @@ -44,7 +44,7 @@ use esp_println::{print, println}; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/ram.rs b/examples/src/bin/ram.rs index 91af1b6f168..bece3c8a998 100644 --- a/examples/src/bin/ram.rs +++ b/examples/src/bin/ram.rs @@ -31,7 +31,7 @@ static mut SOME_ZEROED_DATA: [u8; 8] = [0; 8]; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/rmt_rx.rs b/examples/src/bin/rmt_rx.rs index 3592a39564c..9ad6803f979 100644 --- a/examples/src/bin/rmt_rx.rs +++ b/examples/src/bin/rmt_rx.rs @@ -24,7 +24,7 @@ const WIDTH: usize = 80; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let mut out = io.pins.gpio5; diff --git a/examples/src/bin/rmt_tx.rs b/examples/src/bin/rmt_tx.rs index d7df0f7d7a5..fd5dbc8807d 100644 --- a/examples/src/bin/rmt_tx.rs +++ b/examples/src/bin/rmt_tx.rs @@ -20,7 +20,7 @@ use esp_hal::{ #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/rng.rs b/examples/src/bin/rng.rs index ac240de253d..e981faac46a 100644 --- a/examples/src/bin/rng.rs +++ b/examples/src/bin/rng.rs @@ -11,7 +11,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); let mut rng = Rng::new(peripherals.RNG); // Generate a random word (u32): diff --git a/examples/src/bin/rtc_time.rs b/examples/src/bin/rtc_time.rs index 662531c9a0b..4c0e9c4d189 100644 --- a/examples/src/bin/rtc_time.rs +++ b/examples/src/bin/rtc_time.rs @@ -10,7 +10,7 @@ use esp_hal::{delay::Delay, prelude::*, rtc_cntl::Rtc}; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let rtc = Rtc::new(peripherals.LPWR); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/rtc_watchdog.rs b/examples/src/bin/rtc_watchdog.rs index badda73d47f..e197bd13038 100644 --- a/examples/src/bin/rtc_watchdog.rs +++ b/examples/src/bin/rtc_watchdog.rs @@ -24,7 +24,7 @@ static RWDT: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); let mut rtc = Rtc::new(peripherals.LPWR); rtc.set_interrupt_handler(interrupt_handler); diff --git a/examples/src/bin/serial_interrupts.rs b/examples/src/bin/serial_interrupts.rs index 901ac58c4b1..729f5a3d3a9 100644 --- a/examples/src/bin/serial_interrupts.rs +++ b/examples/src/bin/serial_interrupts.rs @@ -17,7 +17,7 @@ use esp_hal::{ peripherals::UART0, prelude::*, uart::{ - config::{AtCmdConfig, Config as UartConfig}, + config::{AtCmdConfig, Config}, Uart, }, Blocking, @@ -27,7 +27,7 @@ static SERIAL: Mutex>>> = Mutex::new(RefCel #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let delay = Delay::new(&clocks); @@ -49,7 +49,7 @@ fn main() -> ! { let (tx_pin, rx_pin) = (io.pins.gpio43, io.pins.gpio44); } } - let config = UartConfig::default().rx_fifo_full_threshold(30); + let config = Config::default().rx_fifo_full_threshold(30); let mut uart0 = Uart::new_with_config(peripherals.UART0, config, &clocks, tx_pin, rx_pin).unwrap(); diff --git a/examples/src/bin/sleep_timer.rs b/examples/src/bin/sleep_timer.rs index 1e9cbe2a29f..1a0db0116ef 100644 --- a/examples/src/bin/sleep_timer.rs +++ b/examples/src/bin/sleep_timer.rs @@ -11,7 +11,6 @@ use esp_backtrace as _; use esp_hal::{ delay::Delay, entry, - prelude::*, rtc_cntl::{get_reset_reason, get_wakeup_cause, sleep::TimerWakeupSource, Rtc, SocResetReason}, Cpu, }; @@ -19,7 +18,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let delay = Delay::new(&clocks); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_ext0.rs b/examples/src/bin/sleep_timer_ext0.rs index 7b9f62f1ae5..4fef91badb2 100644 --- a/examples/src/bin/sleep_timer_ext0.rs +++ b/examples/src/bin/sleep_timer_ext0.rs @@ -15,7 +15,6 @@ use esp_hal::{ delay::Delay, entry, gpio::Io, - prelude::*, rtc_cntl::{ get_reset_reason, get_wakeup_cause, @@ -29,7 +28,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_ext1.rs b/examples/src/bin/sleep_timer_ext1.rs index 7add24dfa99..bf1c0f881bf 100644 --- a/examples/src/bin/sleep_timer_ext1.rs +++ b/examples/src/bin/sleep_timer_ext1.rs @@ -15,7 +15,6 @@ use esp_hal::{ delay::Delay, entry, gpio::{Io, RtcPin}, - prelude::*, rtc_cntl::{ get_reset_reason, get_wakeup_cause, @@ -29,7 +28,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_lpio.rs b/examples/src/bin/sleep_timer_lpio.rs index 136f9d3b900..05f8a8e04f7 100644 --- a/examples/src/bin/sleep_timer_lpio.rs +++ b/examples/src/bin/sleep_timer_lpio.rs @@ -16,7 +16,6 @@ use esp_hal::{ delay::Delay, entry, gpio::{Io, RtcPinWithResistors}, - prelude::*, rtc_cntl::{ get_reset_reason, get_wakeup_cause, @@ -30,7 +29,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/sleep_timer_rtcio.rs b/examples/src/bin/sleep_timer_rtcio.rs index 47df5af827f..6b33624beaa 100644 --- a/examples/src/bin/sleep_timer_rtcio.rs +++ b/examples/src/bin/sleep_timer_rtcio.rs @@ -20,7 +20,6 @@ use esp_hal::{ entry, gpio, gpio::Io, - prelude::*, rtc_cntl::{ get_reset_reason, get_wakeup_cause, @@ -34,7 +33,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let mut rtc = Rtc::new(peripherals.LPWR); diff --git a/examples/src/bin/software_interrupts.rs b/examples/src/bin/software_interrupts.rs index a26eadd9392..48c1a88bc74 100644 --- a/examples/src/bin/software_interrupts.rs +++ b/examples/src/bin/software_interrupts.rs @@ -26,7 +26,7 @@ static SWINT3: Mutex>>> = Mutex::new(RefCell #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let mut sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT); diff --git a/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs b/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs index 3eba959f865..cd10f9a0cd4 100644 --- a/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs +++ b/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs @@ -42,7 +42,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); cfg_if::cfg_if! { diff --git a/examples/src/bin/spi_loopback.rs b/examples/src/bin/spi_loopback.rs index aff017521b3..17248269422 100644 --- a/examples/src/bin/spi_loopback.rs +++ b/examples/src/bin/spi_loopback.rs @@ -29,7 +29,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/examples/src/bin/spi_loopback_dma.rs b/examples/src/bin/spi_loopback_dma.rs index 419d1ea46ff..b13dd875bb4 100644 --- a/examples/src/bin/spi_loopback_dma.rs +++ b/examples/src/bin/spi_loopback_dma.rs @@ -31,7 +31,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/examples/src/bin/spi_slave_dma.rs b/examples/src/bin/spi_slave_dma.rs index da583f91cd4..f821c49f168 100644 --- a/examples/src/bin/spi_slave_dma.rs +++ b/examples/src/bin/spi_slave_dma.rs @@ -45,7 +45,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let slave_sclk = io.pins.gpio0; diff --git a/examples/src/bin/systimer.rs b/examples/src/bin/systimer.rs index 508ea7e98e6..72d1931ef9c 100644 --- a/examples/src/bin/systimer.rs +++ b/examples/src/bin/systimer.rs @@ -47,7 +47,7 @@ static ALARM2: Mutex< #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let systimer = SystemTimer::new(peripherals.SYSTIMER); println!("SYSTIMER Current value = {}", SystemTimer::now()); diff --git a/examples/src/bin/timer_interrupt.rs b/examples/src/bin/timer_interrupt.rs index 1126ba58a4e..aec50184183 100644 --- a/examples/src/bin/timer_interrupt.rs +++ b/examples/src/bin/timer_interrupt.rs @@ -23,7 +23,7 @@ static TIMER0: Mutex, esp_hal::Blocking>>>> = #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); let timer0 = timg0.timer0; diff --git a/examples/src/bin/touch.rs b/examples/src/bin/touch.rs index 88c15097ded..eef73f705d0 100644 --- a/examples/src/bin/touch.rs +++ b/examples/src/bin/touch.rs @@ -48,7 +48,7 @@ fn interrupt_handler() { #[entry] fn main() -> ! { esp_println::logger::init_logger_from_env(); - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/twai.rs b/examples/src/bin/twai.rs index 380cbf63192..9620ae508dc 100644 --- a/examples/src/bin/twai.rs +++ b/examples/src/bin/twai.rs @@ -35,7 +35,7 @@ use nb::block; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/ulp_riscv_core_basic.rs b/examples/src/bin/ulp_riscv_core_basic.rs index 77e89ae8c23..dcdac147257 100644 --- a/examples/src/bin/ulp_riscv_core_basic.rs +++ b/examples/src/bin/ulp_riscv_core_basic.rs @@ -21,7 +21,7 @@ use esp_println::{print, println}; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let pin = LowPowerOutput::new(io.pins.gpio1); diff --git a/examples/src/bin/usb_serial.rs b/examples/src/bin/usb_serial.rs index 96d8fad6d15..236d5a10bb2 100644 --- a/examples/src/bin/usb_serial.rs +++ b/examples/src/bin/usb_serial.rs @@ -26,7 +26,7 @@ static mut EP_MEMORY: [u32; 1024] = [0; 1024]; #[entry] fn main() -> ! { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/examples/src/bin/usb_serial_jtag.rs b/examples/src/bin/usb_serial_jtag.rs index 2b81ba5492c..a75d0dd486b 100644 --- a/examples/src/bin/usb_serial_jtag.rs +++ b/examples/src/bin/usb_serial_jtag.rs @@ -23,7 +23,7 @@ static USB_SERIAL: Mutex>>> = #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/watchdog.rs b/examples/src/bin/watchdog.rs index 78cd2c252c6..220e9ad4abf 100644 --- a/examples/src/bin/watchdog.rs +++ b/examples/src/bin/watchdog.rs @@ -14,7 +14,7 @@ use esp_println::println; #[entry] fn main() -> ! { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let delay = Delay::new(&clocks); diff --git a/examples/src/bin/wifi_80211_tx.rs b/examples/src/bin/wifi_80211_tx.rs index b129f288641..90c95060055 100644 --- a/examples/src/bin/wifi_80211_tx.rs +++ b/examples/src/bin/wifi_80211_tx.rs @@ -35,7 +35,7 @@ const MAC_ADDRESS: [u8; 6] = [0x00, 0x80, 0x41, 0x13, 0x37, 0x42]; fn main() -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_access_point.rs b/examples/src/bin/wifi_access_point.rs index b79f2dcf54b..e1e01ec525d 100644 --- a/examples/src/bin/wifi_access_point.rs +++ b/examples/src/bin/wifi_access_point.rs @@ -35,7 +35,7 @@ use smoltcp::iface::SocketStorage; fn main() -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_access_point_with_sta.rs b/examples/src/bin/wifi_access_point_with_sta.rs index 69005fd16eb..f58349849e6 100644 --- a/examples/src/bin/wifi_access_point_with_sta.rs +++ b/examples/src/bin/wifi_access_point_with_sta.rs @@ -42,7 +42,7 @@ const PASSWORD: &str = env!("PASSWORD"); fn main() -> ! { esp_println::logger::init_logger(log::LevelFilter::Info); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_bench.rs b/examples/src/bin/wifi_bench.rs index b2ebbad932b..844f291a066 100644 --- a/examples/src/bin/wifi_bench.rs +++ b/examples/src/bin/wifi_bench.rs @@ -52,7 +52,7 @@ const UPLOAD_DOWNLOAD_PORT: u16 = 4323; fn main() -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_ble.rs b/examples/src/bin/wifi_ble.rs index 105034d8192..c71bdb0ec6f 100644 --- a/examples/src/bin/wifi_ble.rs +++ b/examples/src/bin/wifi_ble.rs @@ -36,7 +36,7 @@ use esp_wifi::{ble::controller::BleConnector, initialize, EspWifiInitFor}; fn main() -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_coex.rs b/examples/src/bin/wifi_coex.rs index a62eec72c79..0bd4a4549f7 100644 --- a/examples/src/bin/wifi_coex.rs +++ b/examples/src/bin/wifi_coex.rs @@ -48,7 +48,7 @@ const PASSWORD: &str = env!("PASSWORD"); fn main() -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_dhcp.rs b/examples/src/bin/wifi_dhcp.rs index 1819d551048..a02b52dd2b7 100644 --- a/examples/src/bin/wifi_dhcp.rs +++ b/examples/src/bin/wifi_dhcp.rs @@ -41,7 +41,7 @@ const PASSWORD: &str = env!("PASSWORD"); fn main() -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_embassy_access_point.rs b/examples/src/bin/wifi_embassy_access_point.rs index 4cda2e8cc98..22e65a8e5bc 100644 --- a/examples/src/bin/wifi_embassy_access_point.rs +++ b/examples/src/bin/wifi_embassy_access_point.rs @@ -56,7 +56,7 @@ macro_rules! mk_static { async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_embassy_access_point_with_sta.rs b/examples/src/bin/wifi_embassy_access_point_with_sta.rs index 4524aa76368..42d2d2e43e9 100644 --- a/examples/src/bin/wifi_embassy_access_point_with_sta.rs +++ b/examples/src/bin/wifi_embassy_access_point_with_sta.rs @@ -64,7 +64,7 @@ macro_rules! mk_static { async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_embassy_bench.rs b/examples/src/bin/wifi_embassy_bench.rs index 661e5f7eb83..5a53e8fd4f9 100644 --- a/examples/src/bin/wifi_embassy_bench.rs +++ b/examples/src/bin/wifi_embassy_bench.rs @@ -67,7 +67,7 @@ static mut TX_BUFFER: [u8; TX_BUFFER_SIZE] = [0; TX_BUFFER_SIZE]; async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_embassy_ble.rs b/examples/src/bin/wifi_embassy_ble.rs index 52dc06c4446..282d6e6a17b 100644 --- a/examples/src/bin/wifi_embassy_ble.rs +++ b/examples/src/bin/wifi_embassy_ble.rs @@ -39,7 +39,7 @@ use esp_wifi::{ble::controller::asynch::BleConnector, initialize, EspWifiInitFor async fn main(_spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_embassy_dhcp.rs b/examples/src/bin/wifi_embassy_dhcp.rs index dfc3cc072c4..96d17d926fb 100644 --- a/examples/src/bin/wifi_embassy_dhcp.rs +++ b/examples/src/bin/wifi_embassy_dhcp.rs @@ -50,7 +50,7 @@ const PASSWORD: &str = env!("PASSWORD"); async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_embassy_esp_now.rs b/examples/src/bin/wifi_embassy_esp_now.rs index 743c4b66587..d14d95e0d95 100644 --- a/examples/src/bin/wifi_embassy_esp_now.rs +++ b/examples/src/bin/wifi_embassy_esp_now.rs @@ -26,7 +26,7 @@ use esp_wifi::{ async fn main(_spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_embassy_esp_now_duplex.rs b/examples/src/bin/wifi_embassy_esp_now_duplex.rs index f994e26a7f4..773389ac155 100644 --- a/examples/src/bin/wifi_embassy_esp_now_duplex.rs +++ b/examples/src/bin/wifi_embassy_esp_now_duplex.rs @@ -36,7 +36,7 @@ macro_rules! mk_static { async fn main(spawner: Spawner) -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_esp_now.rs b/examples/src/bin/wifi_esp_now.rs index ae3f8b8c12a..938068aaf95 100644 --- a/examples/src/bin/wifi_esp_now.rs +++ b/examples/src/bin/wifi_esp_now.rs @@ -22,7 +22,7 @@ use esp_wifi::{ fn main() -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_sniffer.rs b/examples/src/bin/wifi_sniffer.rs index f9d81b19e21..2f277af11a0 100644 --- a/examples/src/bin/wifi_sniffer.rs +++ b/examples/src/bin/wifi_sniffer.rs @@ -34,7 +34,7 @@ static KNOWN_SSIDS: Mutex>> = Mutex::new(RefCell::new(B fn main() -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/examples/src/bin/wifi_static_ip.rs b/examples/src/bin/wifi_static_ip.rs index 917043e915d..2c82dcea886 100644 --- a/examples/src/bin/wifi_static_ip.rs +++ b/examples/src/bin/wifi_static_ip.rs @@ -41,7 +41,7 @@ const GATEWAY_IP: &str = env!("GATEWAY_IP"); fn main() -> ! { esp_println::logger::init_logger_from_env(); let (peripherals, clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/hil-test/tests/aes.rs b/hil-test/tests/aes.rs index 00cfcdbedb2..7e9c694884e 100644 --- a/hil-test/tests/aes.rs +++ b/hil-test/tests/aes.rs @@ -25,7 +25,7 @@ mod tests { #[init] fn init() -> Context<'static> { let (peripherals, _clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/hil-test/tests/aes_dma.rs b/hil-test/tests/aes_dma.rs index 2bc940a9899..d3dccfe0ac5 100644 --- a/hil-test/tests/aes_dma.rs +++ b/hil-test/tests/aes_dma.rs @@ -29,7 +29,7 @@ mod tests { #[init] fn init() -> Peripherals { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); peripherals } diff --git a/hil-test/tests/clock_monitor.rs b/hil-test/tests/clock_monitor.rs index de3a94bdc72..724d9165459 100644 --- a/hil-test/tests/clock_monitor.rs +++ b/hil-test/tests/clock_monitor.rs @@ -5,7 +5,7 @@ #![no_std] #![no_main] -use esp_hal::{prelude::*, rtc_cntl::Rtc}; +use esp_hal::rtc_cntl::Rtc; use hil_test as _; struct Context<'a> { @@ -19,7 +19,7 @@ mod tests { #[init] fn init() -> Context<'static> { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); let rtc = Rtc::new(peripherals.LPWR); Context { rtc } diff --git a/hil-test/tests/delay.rs b/hil-test/tests/delay.rs index 8058574f2cb..f171263dc6b 100644 --- a/hil-test/tests/delay.rs +++ b/hil-test/tests/delay.rs @@ -6,7 +6,7 @@ #![no_main] use embedded_hal::delay::DelayNs; -use esp_hal::{delay::Delay, prelude::*}; +use esp_hal::delay::Delay; use hil_test as _; struct Context { @@ -20,7 +20,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (_peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let delay = Delay::new(&clocks); Context { delay } diff --git a/hil-test/tests/dma_mem2mem.rs b/hil-test/tests/dma_mem2mem.rs index 14878ac4685..45e9c9ebcae 100644 --- a/hil-test/tests/dma_mem2mem.rs +++ b/hil-test/tests/dma_mem2mem.rs @@ -10,7 +10,6 @@ use esp_hal::{ dma_buffers, dma_buffers_chunk_size, dma_descriptors, - prelude::*, Blocking, }; use hil_test as _; @@ -39,7 +38,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); let dma = Dma::new(peripherals.DMA); let channel = dma.channel0.configure(false, DmaPriority::Priority0); diff --git a/hil-test/tests/ecc.rs b/hil-test/tests/ecc.rs index c1b294cc135..5400ba84147 100644 --- a/hil-test/tests/ecc.rs +++ b/hil-test/tests/ecc.rs @@ -57,7 +57,7 @@ mod tests { #[init] fn init() -> Context<'static> { let (peripherals, _clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/hil-test/tests/embassy_interrupt_executor.rs b/hil-test/tests/embassy_interrupt_executor.rs index 117f78ca784..67e4f8107ee 100644 --- a/hil-test/tests/embassy_interrupt_executor.rs +++ b/hil-test/tests/embassy_interrupt_executor.rs @@ -14,7 +14,6 @@ use esp_hal::{ software::{SoftwareInterrupt, SoftwareInterruptControl}, Priority, }, - prelude::*, timer::timg::TimerGroup, }; use esp_hal_embassy::InterruptExecutor; @@ -45,7 +44,7 @@ mod test { #[init] fn init() -> SoftwareInterrupt<1> { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0); diff --git a/hil-test/tests/embassy_timers_executors.rs b/hil-test/tests/embassy_timers_executors.rs index 589a52a174e..7627b15a4f2 100644 --- a/hil-test/tests/embassy_timers_executors.rs +++ b/hil-test/tests/embassy_timers_executors.rs @@ -128,7 +128,7 @@ mod test { #[init] fn init() -> (Peripherals, Clocks<'static>) { - esp_hal::init(Config::default()) + esp_hal::init(esp_hal::Config::default()) } #[test] diff --git a/hil-test/tests/get_time.rs b/hil-test/tests/get_time.rs index ed71ea17c0a..6f34c6dd6eb 100644 --- a/hil-test/tests/get_time.rs +++ b/hil-test/tests/get_time.rs @@ -7,7 +7,7 @@ #[cfg(esp32)] use esp_hal::clock::Clocks; -use esp_hal::{delay::Delay, prelude::*}; +use esp_hal::delay::Delay; use hil_test as _; struct Context { @@ -31,7 +31,7 @@ mod tests { #[init] fn init() -> Context { - let (_peripherals, clocks) = esp_hal::init(Config::default()); + let (_peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let delay = Delay::new(&clocks); diff --git a/hil-test/tests/gpio.rs b/hil-test/tests/gpio.rs index bbc97fbafd8..f8f5325fede 100644 --- a/hil-test/tests/gpio.rs +++ b/hil-test/tests/gpio.rs @@ -1,8 +1,8 @@ //! GPIO Test //! //! Folowing pins are used: -//! - GPIO2 -//! - GPIO3 +//! GPIO2 +//! GPIO3 //% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3 //% FEATURES: generic-queue @@ -17,7 +17,6 @@ use esp_hal::{ delay::Delay, gpio::{AnyPin, Gpio2, Gpio3, GpioPin, Input, Io, Level, Output, Pull}, macros::handler, - prelude::*, timer::timg::TimerGroup, InterruptConfigurable, }; @@ -55,7 +54,7 @@ mod tests { #[init] fn init() -> Context<'static> { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX); io.set_interrupt_handler(interrupt_handler); diff --git a/hil-test/tests/i2s.rs b/hil-test/tests/i2s.rs index 97a74e80e05..219eb91dcbb 100644 --- a/hil-test/tests/i2s.rs +++ b/hil-test/tests/i2s.rs @@ -53,7 +53,7 @@ mod tests { #[test] fn test_i2s_loopback() { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let peripherals = peripherals; let clocks = clocks; diff --git a/hil-test/tests/i2s_async.rs b/hil-test/tests/i2s_async.rs index 4aedc47e817..7a9aa0a5ffc 100644 --- a/hil-test/tests/i2s_async.rs +++ b/hil-test/tests/i2s_async.rs @@ -85,7 +85,7 @@ mod tests { async fn test_i2s_loopback() { let spawner = embassy_executor::Spawner::for_current_executor().await; - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let peripherals = peripherals; let clocks = clocks; diff --git a/hil-test/tests/interrupt.rs b/hil-test/tests/interrupt.rs index ea0173d9492..8f6d63ea618 100644 --- a/hil-test/tests/interrupt.rs +++ b/hil-test/tests/interrupt.rs @@ -65,7 +65,7 @@ mod tests { #[init] fn init() -> Context { let (peripherals, _clocks) = esp_hal::init({ - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); config }); diff --git a/hil-test/tests/lcd_cam_i8080.rs b/hil-test/tests/lcd_cam_i8080.rs index 189b667e1a7..4237335deb1 100644 --- a/hil-test/tests/lcd_cam_i8080.rs +++ b/hil-test/tests/lcd_cam_i8080.rs @@ -11,7 +11,7 @@ use esp_hal::{ dma_buffers, gpio::DummyPin, lcd_cam::{ - lcd::i8080::{self, Command, TxEightBits, I8080}, + lcd::i8080::{Command, Config, TxEightBits, I8080}, LcdCam, }, prelude::*, @@ -35,7 +35,7 @@ mod tests { #[init] fn init() -> Context<'static> { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let dma = Dma::new(peripherals.DMA); let lcd_cam = LcdCam::new(peripherals.LCD_CAM); let (tx_buffer, tx_descriptors, _, _) = dma_buffers!(DATA_SIZE, 0); @@ -70,7 +70,7 @@ mod tests { ctx.tx_descriptors, pins, 20.MHz(), - i8080::Config::default(), + Config::default(), &ctx.clocks, ); @@ -103,7 +103,7 @@ mod tests { ctx.tx_descriptors, pins, 20.MHz(), - i8080::Config::default(), + Config::default(), &ctx.clocks, ); diff --git a/hil-test/tests/lcd_cam_i8080_async.rs b/hil-test/tests/lcd_cam_i8080_async.rs index 0114857bf94..a5b2c9ef487 100644 --- a/hil-test/tests/lcd_cam_i8080_async.rs +++ b/hil-test/tests/lcd_cam_i8080_async.rs @@ -12,10 +12,7 @@ use esp_hal::{ dma_buffers, gpio::DummyPin, lcd_cam::{ - lcd::{ - i8080, - i8080::{Command, TxEightBits, I8080}, - }, + lcd::i8080::{Command, Config, TxEightBits, I8080}, LcdCam, }, prelude::*, @@ -39,7 +36,7 @@ mod tests { #[init] async fn init() -> Context<'static> { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let dma = Dma::new(peripherals.DMA); let lcd_cam = LcdCam::new_async(peripherals.LCD_CAM); @@ -74,7 +71,7 @@ mod tests { ctx.tx_descriptors, pins, 20.MHz(), - i8080::Config::default(), + Config::default(), &ctx.clocks, ); @@ -107,7 +104,7 @@ mod tests { ctx.tx_descriptors, pins, 20.MHz(), - i8080::Config::default(), + Config::default(), &ctx.clocks, ); diff --git a/hil-test/tests/pcnt.rs b/hil-test/tests/pcnt.rs index 8c07f5ca3d4..dbf806c17f3 100644 --- a/hil-test/tests/pcnt.rs +++ b/hil-test/tests/pcnt.rs @@ -14,7 +14,6 @@ use esp_hal::{ channel::{EdgeMode, PcntInputConfig, PcntSource}, Pcnt, }, - prelude::*, }; use hil_test as _; @@ -32,7 +31,7 @@ mod tests { #[init] fn init() -> Context<'static> { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/qspi_read.rs b/hil-test/tests/qspi_read.rs index cae18ef39f7..6abeab451db 100644 --- a/hil-test/tests/qspi_read.rs +++ b/hil-test/tests/qspi_read.rs @@ -13,11 +13,10 @@ #![no_main] use esp_hal::{ - clock::{ClockControl, Clocks}, + clock::Clocks, dma::{Channel, Dma, DmaPriority, DmaRxBuf}, dma_buffers, gpio::{GpioPin, Io, Level, Output}, - peripherals::Peripherals, prelude::*, spi::{ master::{Address, Command, Spi, SpiDma}, @@ -25,7 +24,6 @@ use esp_hal::{ SpiDataMode, SpiMode, }, - system::SystemControl, Blocking, }; use hil_test as _; @@ -101,9 +99,7 @@ mod tests { #[init] fn init() -> Context { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let miso = io.pins.gpio2; diff --git a/hil-test/tests/qspi_write.rs b/hil-test/tests/qspi_write.rs index 70a35d411de..bc2b01f9273 100644 --- a/hil-test/tests/qspi_write.rs +++ b/hil-test/tests/qspi_write.rs @@ -15,7 +15,7 @@ #![no_main] use esp_hal::{ - clock::{ClockControl, Clocks}, + clock::Clocks, dma::{Channel, Dma, DmaPriority, DmaTxBuf}, dma_buffers, gpio::{Io, Pull}, @@ -24,7 +24,6 @@ use esp_hal::{ unit::Unit, Pcnt, }, - peripherals::Peripherals, prelude::*, spi::{ master::{Address, Command, Spi, SpiDma}, @@ -32,7 +31,6 @@ use esp_hal::{ SpiDataMode, SpiMode, }, - system::SystemControl, Blocking, }; use hil_test as _; @@ -112,9 +110,7 @@ mod tests { #[init] fn init() -> Context { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let mosi = io.pins.gpio2; diff --git a/hil-test/tests/qspi_write_read.rs b/hil-test/tests/qspi_write_read.rs index 4d98c7b9519..602a6a964f3 100644 --- a/hil-test/tests/qspi_write_read.rs +++ b/hil-test/tests/qspi_write_read.rs @@ -15,11 +15,10 @@ #![no_main] use esp_hal::{ - clock::{ClockControl, Clocks}, + clock::Clocks, dma::{Channel, Dma, DmaPriority, DmaRxBuf, DmaTxBuf}, dma_buffers, gpio::{GpioPin, Io, Level, Output}, - peripherals::Peripherals, prelude::*, spi::{ master::{Address, Command, Spi, SpiDma}, @@ -27,7 +26,6 @@ use esp_hal::{ SpiDataMode, SpiMode, }, - system::SystemControl, Blocking, }; use hil_test as _; @@ -103,9 +101,7 @@ mod tests { #[init] fn init() -> Context { - let peripherals = Peripherals::take(); - let system = SystemControl::new(peripherals.SYSTEM); - let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let mosi = io.pins.gpio2; diff --git a/hil-test/tests/rmt.rs b/hil-test/tests/rmt.rs index 5948a253214..722444a348a 100644 --- a/hil-test/tests/rmt.rs +++ b/hil-test/tests/rmt.rs @@ -25,7 +25,7 @@ mod tests { #[test] #[timeout(1)] fn rmt_loopback() { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/rsa.rs b/hil-test/tests/rsa.rs index 2cd431ea4f2..389fc01df31 100644 --- a/hil-test/tests/rsa.rs +++ b/hil-test/tests/rsa.rs @@ -57,7 +57,7 @@ mod tests { #[init] fn init() -> Context<'static> { - let (peripherals, _clocks) = esp_hal::init(Config::default()); + let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default()); let mut rsa = Rsa::new(peripherals.RSA); nb::block!(rsa.ready()).unwrap(); diff --git a/hil-test/tests/sha.rs b/hil-test/tests/sha.rs index 91278c5d0ef..adc7acc9190 100644 --- a/hil-test/tests/sha.rs +++ b/hil-test/tests/sha.rs @@ -166,9 +166,9 @@ mod tests { cfg_if::cfg_if! { if #[cfg(feature = "esp32")] { // FIXME: max speed fails...? - let config = Config::default(); + let config = esp_hal::Config::default(); } else { - let mut config = Config::default(); + let mut config = esp_hal::Config::default(); config.cpu_clock = CpuClock::max(); } } diff --git a/hil-test/tests/spi_full_duplex.rs b/hil-test/tests/spi_full_duplex.rs index fa14ea2b926..e38ba9833b0 100644 --- a/hil-test/tests/spi_full_duplex.rs +++ b/hil-test/tests/spi_full_duplex.rs @@ -34,7 +34,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/spi_full_duplex_dma.rs b/hil-test/tests/spi_full_duplex_dma.rs index 0081267a0cf..e1ef46c05ef 100644 --- a/hil-test/tests/spi_full_duplex_dma.rs +++ b/hil-test/tests/spi_full_duplex_dma.rs @@ -14,7 +14,6 @@ #![no_main] use esp_hal::{ - clock::Clocks, dma::{Dma, DmaPriority, DmaRxBuf, DmaTxBuf}, dma_buffers, gpio::Io, @@ -48,13 +47,12 @@ struct Context { #[embedded_test::tests] mod tests { use defmt::assert_eq; - use esp_hal::dma::{DmaRxBuf, DmaTxBuf}; use super::*; #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/spi_full_duplex_dma_async.rs b/hil-test/tests/spi_full_duplex_dma_async.rs index 7159e8a7726..674ac477e7e 100644 --- a/hil-test/tests/spi_full_duplex_dma_async.rs +++ b/hil-test/tests/spi_full_duplex_dma_async.rs @@ -70,7 +70,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let pcnt = Pcnt::new(peripherals.PCNT); diff --git a/hil-test/tests/spi_full_duplex_dma_pcnt.rs b/hil-test/tests/spi_full_duplex_dma_pcnt.rs index 6fb816a0efc..0581e8e5746 100644 --- a/hil-test/tests/spi_full_duplex_dma_pcnt.rs +++ b/hil-test/tests/spi_full_duplex_dma_pcnt.rs @@ -64,7 +64,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/spi_half_duplex_read.rs b/hil-test/tests/spi_half_duplex_read.rs index 6d036f1f540..b8892c79dd2 100644 --- a/hil-test/tests/spi_half_duplex_read.rs +++ b/hil-test/tests/spi_half_duplex_read.rs @@ -54,7 +54,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/spi_half_duplex_write.rs b/hil-test/tests/spi_half_duplex_write.rs index 2185b252eaa..5d21e0297bd 100644 --- a/hil-test/tests/spi_half_duplex_write.rs +++ b/hil-test/tests/spi_half_duplex_write.rs @@ -63,7 +63,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); let sclk = io.pins.gpio0; diff --git a/hil-test/tests/systimer.rs b/hil-test/tests/systimer.rs index 6dd3b95d1c0..ffaf473814f 100644 --- a/hil-test/tests/systimer.rs +++ b/hil-test/tests/systimer.rs @@ -104,7 +104,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let systimer = SystemTimer::new(peripherals.SYSTIMER); static UNIT0: StaticCell> = StaticCell::new(); diff --git a/hil-test/tests/twai.rs b/hil-test/tests/twai.rs index 79b1aa9ac11..fe193c60255 100644 --- a/hil-test/tests/twai.rs +++ b/hil-test/tests/twai.rs @@ -35,7 +35,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/uart.rs b/hil-test/tests/uart.rs index ce54367bda8..f5e0e4e4f1d 100644 --- a/hil-test/tests/uart.rs +++ b/hil-test/tests/uart.rs @@ -37,7 +37,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/uart_async.rs b/hil-test/tests/uart_async.rs index e7fd7f12073..8a5ef5b4cb7 100644 --- a/hil-test/tests/uart_async.rs +++ b/hil-test/tests/uart_async.rs @@ -12,7 +12,7 @@ #![no_std] #![no_main] -use esp_hal::{gpio::Io, peripherals::UART0, prelude::*, uart::Uart, Async}; +use esp_hal::{gpio::Io, peripherals::UART0, uart::Uart, Async}; use hil_test as _; struct Context { @@ -28,7 +28,7 @@ mod tests { #[init] async fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/uart_tx_rx.rs b/hil-test/tests/uart_tx_rx.rs index ff0c599d173..a6ce3a7825c 100644 --- a/hil-test/tests/uart_tx_rx.rs +++ b/hil-test/tests/uart_tx_rx.rs @@ -35,7 +35,7 @@ mod tests { #[init] fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/uart_tx_rx_async.rs b/hil-test/tests/uart_tx_rx_async.rs index c92fa8090ef..0209a58a06d 100644 --- a/hil-test/tests/uart_tx_rx_async.rs +++ b/hil-test/tests/uart_tx_rx_async.rs @@ -15,7 +15,6 @@ use esp_hal::{ gpio::Io, peripherals::{UART0, UART1}, - prelude::*, uart::{UartRx, UartTx}, Async, }; @@ -35,7 +34,7 @@ mod tests { #[init] async fn init() -> Context { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); diff --git a/hil-test/tests/usb_serial_jtag.rs b/hil-test/tests/usb_serial_jtag.rs index 854e65e4cb0..7e2216221a0 100644 --- a/hil-test/tests/usb_serial_jtag.rs +++ b/hil-test/tests/usb_serial_jtag.rs @@ -8,12 +8,12 @@ #[cfg(test)] #[embedded_test::tests] mod tests { - use esp_hal::{prelude::*, timer::timg::TimerGroup, usb_serial_jtag::UsbSerialJtag}; + use esp_hal::{timer::timg::TimerGroup, usb_serial_jtag::UsbSerialJtag}; use hil_test as _; #[test] fn creating_peripheral_does_not_break_debug_connection() { - let (peripherals, clocks) = esp_hal::init(Config::default()); + let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default()); let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); esp_hal_embassy::init(&clocks, timg0.timer0);