From a09ae820747f8a43634394ddbc5ed91720e9bbd7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C3=A1niel=20Buga?= Date: Sat, 9 Nov 2024 13:34:41 +0100 Subject: [PATCH] p.GPIO --- esp-hal/CHANGELOG.md | 2 +- esp-hal/MIGRATING-0.21.md | 2 +- esp-hal/src/analog/adc/mod.rs | 9 +- esp-hal/src/analog/dac.rs | 4 +- esp-hal/src/dma/mod.rs | 8 +- esp-hal/src/etm.rs | 4 +- esp-hal/src/gpio/etm.rs | 4 +- esp-hal/src/gpio/lp_io.rs | 2 +- esp-hal/src/gpio/mod.rs | 87 ++++---- esp-hal/src/gpio/rtc_io.rs | 2 +- esp-hal/src/i2c/master/mod.rs | 4 +- esp-hal/src/i2s/master.rs | 8 +- esp-hal/src/lcd_cam/cam.rs | 24 +-- esp-hal/src/lcd_cam/lcd/i8080.rs | 18 +- esp-hal/src/ledc/mod.rs | 2 +- esp-hal/src/lib.rs | 2 +- esp-hal/src/mcpwm/mod.rs | 2 +- esp-hal/src/mcpwm/operator.rs | 4 +- esp-hal/src/peripheral.rs | 102 ++++++---- esp-hal/src/rmt.rs | 2 +- esp-hal/src/rng.rs | 4 +- esp-hal/src/rom/md5.rs | 4 +- esp-hal/src/rtc_cntl/sleep/esp32c6.rs | 34 ++-- esp-hal/src/soc/esp32/efuse/mod.rs | 2 +- esp-hal/src/soc/esp32/gpio.rs | 47 +---- esp-hal/src/soc/esp32/peripherals.rs | 146 +++++++++----- esp-hal/src/soc/esp32c2/efuse/mod.rs | 2 +- esp-hal/src/soc/esp32c2/gpio.rs | 17 -- esp-hal/src/soc/esp32c2/peripherals.rs | 88 +++++---- esp-hal/src/soc/esp32c3/efuse/mod.rs | 2 +- esp-hal/src/soc/esp32c3/gpio.rs | 25 --- esp-hal/src/soc/esp32c3/peripherals.rs | 106 ++++++---- esp-hal/src/soc/esp32c6/efuse/mod.rs | 2 +- esp-hal/src/soc/esp32c6/gpio.rs | 34 ---- esp-hal/src/soc/esp32c6/peripherals.rs | 187 +++++++++++------- esp-hal/src/soc/esp32h2/efuse/mod.rs | 2 +- esp-hal/src/soc/esp32h2/gpio.rs | 36 +--- esp-hal/src/soc/esp32h2/peripherals.rs | 164 ++++++++------- esp-hal/src/soc/esp32s2/efuse/mod.rs | 2 +- esp-hal/src/soc/esp32s2/gpio.rs | 47 ----- esp-hal/src/soc/esp32s2/peripherals.rs | 144 +++++++++----- esp-hal/src/soc/esp32s3/efuse/mod.rs | 2 +- esp-hal/src/soc/esp32s3/gpio.rs | 48 ----- esp-hal/src/soc/esp32s3/peripherals.rs | 165 ++++++++++------ esp-hal/src/spi/master.rs | 8 +- esp-hal/src/spi/slave.rs | 8 +- esp-hal/src/touch.rs | 2 +- esp-hal/src/twai/mod.rs | 8 +- esp-hal/src/uart.rs | 20 +- examples/src/bin/adc.rs | 6 +- examples/src/bin/adc_cal.rs | 4 +- examples/src/bin/advanced_serial.rs | 4 +- examples/src/bin/blinky.rs | 2 +- examples/src/bin/blinky_erased_pins.rs | 10 +- examples/src/bin/dac.rs | 8 +- examples/src/bin/embassy_i2c.rs | 4 +- .../embassy_i2c_bmp180_calibration_data.rs | 4 +- examples/src/bin/embassy_i2s_parallel.rs | 18 +- examples/src/bin/embassy_i2s_read.rs | 8 +- examples/src/bin/embassy_i2s_sound.rs | 6 +- examples/src/bin/embassy_multicore.rs | 2 +- .../src/bin/embassy_multicore_interrupt.rs | 2 +- examples/src/bin/embassy_parl_io_rx.rs | 8 +- examples/src/bin/embassy_parl_io_tx.rs | 12 +- examples/src/bin/embassy_rmt_rx.rs | 8 +- examples/src/bin/embassy_rmt_tx.rs | 2 +- examples/src/bin/embassy_serial.rs | 12 +- examples/src/bin/embassy_spi.rs | 8 +- examples/src/bin/embassy_touch.rs | 4 +- examples/src/bin/embassy_twai.rs | 6 +- examples/src/bin/embassy_usb_serial.rs | 4 +- examples/src/bin/embassy_wait.rs | 4 +- examples/src/bin/etm_blinky_systimer.rs | 2 +- examples/src/bin/etm_gpio.rs | 4 +- examples/src/bin/gpio_interrupt.rs | 6 +- examples/src/bin/hello_world.rs | 12 +- .../src/bin/i2c_bmp180_calibration_data.rs | 4 +- examples/src/bin/i2c_display.rs | 4 +- examples/src/bin/i2s_parallel.rs | 18 +- examples/src/bin/i2s_read.rs | 8 +- examples/src/bin/i2s_sound.rs | 6 +- examples/src/bin/ieee802154_sniffer.rs | 4 +- examples/src/bin/lcd_cam_ov2640.rs | 28 +-- examples/src/bin/lcd_i8080.rs | 26 +-- examples/src/bin/ledc.rs | 2 +- examples/src/bin/lp_core_basic.rs | 2 +- examples/src/bin/lp_core_i2c.rs | 4 +- examples/src/bin/lp_core_uart.rs | 8 +- examples/src/bin/mcpwm.rs | 2 +- examples/src/bin/parl_io_rx.rs | 8 +- examples/src/bin/parl_io_tx.rs | 12 +- examples/src/bin/pcnt_encoder.rs | 4 +- examples/src/bin/qspi_flash.rs | 24 +-- examples/src/bin/rmt_rx.rs | 8 +- examples/src/bin/rmt_tx.rs | 2 +- examples/src/bin/serial_interrupts.rs | 12 +- examples/src/bin/sleep_timer_ext0.rs | 2 +- examples/src/bin/sleep_timer_ext1.rs | 4 +- examples/src/bin/sleep_timer_lpio.rs | 4 +- examples/src/bin/sleep_timer_rtcio.rs | 8 +- .../spi_halfduplex_read_manufacturer_id.rs | 24 +-- examples/src/bin/spi_loopback.rs | 6 +- examples/src/bin/spi_loopback_dma.rs | 8 +- examples/src/bin/spi_loopback_dma_psram.rs | 6 +- examples/src/bin/spi_slave_dma.rs | 18 +- examples/src/bin/touch.rs | 4 +- examples/src/bin/twai.rs | 6 +- examples/src/bin/ulp_riscv_core_basic.rs | 2 +- examples/src/bin/usb_serial.rs | 4 +- examples/src/bin/wifi_ble.rs | 4 +- examples/src/bin/wifi_embassy_ble.rs | 4 +- hil-test/src/lib.rs | 28 +-- hil-test/tests/embassy_interrupt_spi_dma.rs | 1 - hil-test/tests/gpio.rs | 4 +- hil-test/tests/lcd_cam_i8080.rs | 39 ++-- hil-test/tests/spi_full_duplex.rs | 2 +- hil-test/tests/spi_half_duplex_read.rs | 2 +- hil-test/tests/spi_half_duplex_write.rs | 2 +- hil-test/tests/spi_half_duplex_write_psram.rs | 4 +- 119 files changed, 1100 insertions(+), 1090 deletions(-) diff --git a/esp-hal/CHANGELOG.md b/esp-hal/CHANGELOG.md index e19c5d07ee7..b056d84a6de 100644 --- a/esp-hal/CHANGELOG.md +++ b/esp-hal/CHANGELOG.md @@ -171,7 +171,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0 - SPI transactions are now cancelled if the transfer object (or async Future) is dropped. (#2216) - The DMA channel types have been removed from peripherals (#2261) - `I2C` driver renamed to `I2c` (#2320) -- The GPIO pins are now accessible via `Peripherals` and are no longer part of the `Io` struct (#2508) +- The GPIO pins are now accessible via `Peripherals` and are no longer part of the `Io` struct (#2508) ### Fixed diff --git a/esp-hal/MIGRATING-0.21.md b/esp-hal/MIGRATING-0.21.md index 0b74c31f1ea..9304bddd0b6 100644 --- a/esp-hal/MIGRATING-0.21.md +++ b/esp-hal/MIGRATING-0.21.md @@ -8,7 +8,7 @@ let peripherals = esp_hal::init(Default::default()); -let io = Io::new(peripherals.GPIO, peripherals.IOMUX); -let pin = io.pins.gpio5; -+let pin = peripherals.pins.gpio5; ++let pin = peripherals.GPIO5; ``` ### `Io` constructor changes diff --git a/esp-hal/src/analog/adc/mod.rs b/esp-hal/src/analog/adc/mod.rs index 053e0ae1f8d..0f8f76067c5 100644 --- a/esp-hal/src/analog/adc/mod.rs +++ b/esp-hal/src/analog/adc/mod.rs @@ -31,14 +31,11 @@ //! # use esp_hal::analog::adc::Attenuation; //! # use esp_hal::analog::adc::Adc; //! # use esp_hal::delay::Delay; -#![cfg_attr(esp32, doc = "let analog_pin = peripherals.pins.gpio32;")] -#![cfg_attr( - any(esp32s2, esp32s3), - doc = "let analog_pin = peripherals.pins.gpio3;" -)] +#![cfg_attr(esp32, doc = "let analog_pin = peripherals.GPIO32;")] +#![cfg_attr(any(esp32s2, esp32s3), doc = "let analog_pin = peripherals.GPIO3;")] #![cfg_attr( not(any(esp32, esp32s2, esp32s3)), - doc = "let analog_pin = peripherals.pins.gpio2;" + doc = "let analog_pin = peripherals.GPIO2;" )] //! let mut adc1_config = AdcConfig::new(); //! let mut pin = adc1_config.enable_pin( diff --git a/esp-hal/src/analog/dac.rs b/esp-hal/src/analog/dac.rs index 9956375d67c..246dfa796c0 100644 --- a/esp-hal/src/analog/dac.rs +++ b/esp-hal/src/analog/dac.rs @@ -20,8 +20,8 @@ //! # use esp_hal::analog::dac::Dac; //! # use esp_hal::delay::Delay; //! # use embedded_hal::delay::DelayNs; -#![cfg_attr(esp32, doc = "let dac1_pin = peripherals.pins.gpio25;")] -#![cfg_attr(esp32s2, doc = "let dac1_pin = peripherals.pins.gpio17;")] +#![cfg_attr(esp32, doc = "let dac1_pin = peripherals.GPIO25;")] +#![cfg_attr(esp32s2, doc = "let dac1_pin = peripherals.GPIO17;")] //! let mut dac1 = Dac::new(peripherals.DAC1, dac1_pin); //! //! let mut delay = Delay::new(); diff --git a/esp-hal/src/dma/mod.rs b/esp-hal/src/dma/mod.rs index de519b3e3c1..e88776e423b 100644 --- a/esp-hal/src/dma/mod.rs +++ b/esp-hal/src/dma/mod.rs @@ -23,10 +23,10 @@ //! 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 sclk = peripherals.pins.gpio0; -//! let miso = peripherals.pins.gpio2; -//! let mosi = peripherals.pins.gpio4; -//! let cs = peripherals.pins.gpio5; +//! let sclk = peripherals.GPIO0; +//! let miso = peripherals.GPIO2; +//! let mosi = peripherals.GPIO4; +//! let cs = peripherals.GPIO5; //! //! let mut spi = Spi::new_with_config( //! peripherals.SPI2, diff --git a/esp-hal/src/etm.rs b/esp-hal/src/etm.rs index c592978e73e..5276eadcccf 100644 --- a/esp-hal/src/etm.rs +++ b/esp-hal/src/etm.rs @@ -28,8 +28,8 @@ //! # use esp_hal::gpio::Pull; //! # use esp_hal::gpio::Level; //! -//! let mut led = peripherals.pins.gpio1; -//! let button = peripherals.pins.gpio9; +//! let mut led = peripherals.GPIO1; +//! let button = peripherals.GPIO9; //! //! // setup ETM //! let gpio_ext = Channels::new(peripherals.GPIO_SD); diff --git a/esp-hal/src/gpio/etm.rs b/esp-hal/src/gpio/etm.rs index a3fe2d22448..4ff74e67804 100644 --- a/esp-hal/src/gpio/etm.rs +++ b/esp-hal/src/gpio/etm.rs @@ -32,8 +32,8 @@ //! # use esp_hal::gpio::Pull; //! # use esp_hal::gpio::Level; //! # -//! # let mut led = peripherals.pins.gpio1; -//! # let button = peripherals.pins.gpio9; +//! # let mut led = peripherals.GPIO1; +//! # let button = peripherals.GPIO9; //! //! let gpio_ext = Channels::new(peripherals.GPIO_SD); //! let led_task = gpio_ext.channel0_task.toggle( diff --git a/esp-hal/src/gpio/lp_io.rs b/esp-hal/src/gpio/lp_io.rs index f744f1916f2..947a9efc7e8 100644 --- a/esp-hal/src/gpio/lp_io.rs +++ b/esp-hal/src/gpio/lp_io.rs @@ -23,7 +23,7 @@ //! use esp_hal::gpio::lp_io::LowPowerOutput; //! // configure GPIO 1 as LP output pin //! let lp_pin: LowPowerOutput<'_, 1> = -//! LowPowerOutput::new(peripherals.pins.gpio1); +//! LowPowerOutput::new(peripherals.GPIO1); //! # } //! ``` diff --git a/esp-hal/src/gpio/mod.rs b/esp-hal/src/gpio/mod.rs index d07c891d29d..f01791c65f6 100644 --- a/esp-hal/src/gpio/mod.rs +++ b/esp-hal/src/gpio/mod.rs @@ -52,7 +52,7 @@ //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::gpio::{Io, Level, Output}; -//! let mut led = Output::new(peripherals.pins.gpio5, Level::High); +//! let mut led = Output::new(peripherals.GPIO5, Level::High); //! # } //! ``` //! @@ -70,11 +70,18 @@ use portable_atomic::{AtomicPtr, Ordering}; use procmacros::ram; +#[cfg(any(lp_io, rtc_cntl))] +use crate::peripherals::gpio::{handle_rtcio, handle_rtcio_with_resistors}; pub use crate::soc::gpio::*; use crate::{ interrupt::{self, InterruptHandler, Priority}, peripheral::{Peripheral, PeripheralRef}, - peripherals::{Interrupt, GPIO, IO_MUX}, + peripherals::{ + gpio::{handle_gpio_input, handle_gpio_output, AnyPinInner}, + Interrupt, + GPIO, + IO_MUX, + }, private::{self, Sealed}, InterruptConfigurable, DEFAULT_INTERRUPT_HANDLER, @@ -715,6 +722,9 @@ impl Bank1GpioRegisterAccess { /// GPIO pin pub struct GpioPin; +/// Type-erased GPIO pin +pub struct AnyPin(pub(crate) AnyPinInner); + impl GpioPin where Self: Pin, @@ -905,20 +915,20 @@ macro_rules! if_rtcio_pin { #[macro_export] macro_rules! io_type { (Input, $gpionum:literal) => { - impl $crate::gpio::InputPin for GpioPin<$gpionum> {} + impl $crate::gpio::InputPin for $crate::gpio::GpioPin<$gpionum> {} }; (Output, $gpionum:literal) => { - impl $crate::gpio::OutputPin for GpioPin<$gpionum> {} + impl $crate::gpio::OutputPin for $crate::gpio::GpioPin<$gpionum> {} }; (Analog, $gpionum:literal) => { // FIXME: the implementation shouldn't be in the GPIO module #[cfg(any(esp32c2, esp32c3, esp32c6, esp32h2))] - impl $crate::gpio::AnalogPin for GpioPin<$gpionum> { + impl $crate::gpio::AnalogPin for $crate::gpio::GpioPin<$gpionum> { /// Configures the pin for analog mode. fn set_analog(&self, _: $crate::private::Internal) { use $crate::peripherals::GPIO; - get_io_mux_reg($gpionum).modify(|_, w| unsafe { + $crate::gpio::get_io_mux_reg($gpionum).modify(|_, w| unsafe { w.mcu_sel().bits(1); w.fun_ie().clear_bit(); w.fun_wpu().clear_bit(); @@ -950,91 +960,70 @@ macro_rules! gpio { )+ ) => { paste::paste! { - /// Pins available on this chip - pub struct Pins { - $( - #[doc = concat!("GPIO pin number ", $gpionum, ".")] - pub [< gpio $gpionum >] : GpioPin<$gpionum>, - )+ - } - - impl Pins { - /// Unsafely create GPIO pins. - /// - /// # Safety - /// - /// The caller must ensure that only one instance of a pin is in use at one time. - pub unsafe fn steal() -> Self { - Self { - $( - [< gpio $gpionum >]: GpioPin::steal(), - )+ - } - } - } - $( $( $crate::io_type!($type, $gpionum); )* - impl $crate::gpio::Pin for GpioPin<$gpionum> { + impl $crate::gpio::Pin for $crate::gpio::GpioPin<$gpionum> { fn number(&self) -> u8 { $gpionum } - fn degrade_pin(&self, _: $crate::private::Internal) -> AnyPin { - AnyPin($crate::gpio::AnyPinInner::[< Gpio $gpionum >](unsafe { Self::steal() })) + fn degrade_pin(&self, _: $crate::private::Internal) -> $crate::gpio::AnyPin { + $crate::gpio::AnyPin(AnyPinInner::[< Gpio $gpionum >](unsafe { Self::steal() })) } fn gpio_bank(&self, _: $crate::private::Internal) -> $crate::gpio::GpioRegisterAccess { $crate::gpio::GpioRegisterAccess::from($gpionum) } - fn output_signals(&self, _: $crate::private::Internal) -> &[(AlternateFunction, OutputSignal)] { + fn output_signals(&self, _: $crate::private::Internal) -> &[($crate::gpio::AlternateFunction, $crate::gpio::OutputSignal)] { &[ $( $( - (AlternateFunction::[< Function $af_output_num >], OutputSignal::$af_output_signal ), + ( + $crate::gpio::AlternateFunction::[< Function $af_output_num >], + $crate::gpio::OutputSignal::$af_output_signal + ), )* )? ] } - fn input_signals(&self, _: $crate::private::Internal) -> &[(AlternateFunction, InputSignal)] { + fn input_signals(&self, _: $crate::private::Internal) -> &[($crate::gpio::AlternateFunction, $crate::gpio::InputSignal)] { &[ $( $( - (AlternateFunction::[< Function $af_input_num >], InputSignal::$af_input_signal ), + ( + $crate::gpio::AlternateFunction::[< Function $af_input_num >], + $crate::gpio::InputSignal::$af_input_signal + ), )* )? ] } } - impl From> for AnyPin { - fn from(pin: GpioPin<$gpionum>) -> Self { - use $crate::gpio::Pin; - pin.degrade() + impl From<$crate::gpio::GpioPin<$gpionum>> for $crate::gpio::AnyPin { + fn from(pin: $crate::gpio::GpioPin<$gpionum>) -> Self { + $crate::gpio::Pin::degrade(pin) } } )+ pub(crate) enum AnyPinInner { $( - [](GpioPin<$gpionum>), + []($crate::gpio::GpioPin<$gpionum>), )+ } - /// Type-erased GPIO pin - pub struct AnyPin(pub(crate) AnyPinInner); - - impl $crate::peripheral::Peripheral for AnyPin { - type P = AnyPin; + impl $crate::peripheral::Peripheral for $crate::gpio::AnyPin { + type P = $crate::gpio::AnyPin; unsafe fn clone_unchecked(&self) -> Self { match self.0 { $(AnyPinInner::[](_) => { - Self(AnyPinInner::[< Gpio $gpionum >](unsafe { GpioPin::steal() })) + Self(AnyPinInner::[< Gpio $gpionum >](unsafe { $crate::gpio::GpioPin::steal() })) })+ } } @@ -1043,7 +1032,6 @@ macro_rules! gpio { // These macros call the code block on the actually contained GPIO pin. #[doc(hidden)] - #[macro_export] macro_rules! handle_gpio_output { ($this:expr, $inner:ident, $code:tt) => { match $this { @@ -1060,7 +1048,6 @@ macro_rules! gpio { } #[doc(hidden)] - #[macro_export] macro_rules! handle_gpio_input { ($this:expr, $inner:ident, $code:tt) => { match $this { @@ -1077,7 +1064,6 @@ macro_rules! gpio { cfg_if::cfg_if! { if #[cfg(any(lp_io, rtc_cntl))] { #[doc(hidden)] - #[macro_export] macro_rules! handle_rtcio { ($this:expr, $inner:ident, $code:tt) => { match $this { @@ -1094,7 +1080,6 @@ macro_rules! gpio { } #[doc(hidden)] - #[macro_export] macro_rules! handle_rtcio_with_resistors { ($this:expr, $inner:ident, $code:tt) => { match $this { diff --git a/esp-hal/src/gpio/rtc_io.rs b/esp-hal/src/gpio/rtc_io.rs index be7aaf4f501..beebc37e3d4 100644 --- a/esp-hal/src/gpio/rtc_io.rs +++ b/esp-hal/src/gpio/rtc_io.rs @@ -24,7 +24,7 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::gpio::rtc_io::LowPowerOutput; //! // configure GPIO 1 as ULP output pin -//! let lp_pin = LowPowerOutput::<'static, 1>::new(peripherals.pins.gpio1); +//! let lp_pin = LowPowerOutput::<'static, 1>::new(peripherals.GPIO1); //! # } //! ``` diff --git a/esp-hal/src/i2c/master/mod.rs b/esp-hal/src/i2c/master/mod.rs index f086982d53c..7515d2ed8c4 100644 --- a/esp-hal/src/i2c/master/mod.rs +++ b/esp-hal/src/i2c/master/mod.rs @@ -26,8 +26,8 @@ //! peripherals.I2C0, //! Config::default(), //! ) -//! .with_sda(peripherals.pins.gpio1) -//! .with_scl(peripherals.pins.gpio2); +//! .with_sda(peripherals.GPIO1) +//! .with_scl(peripherals.GPIO2); //! //! loop { //! let mut data = [0u8; 22]; diff --git a/esp-hal/src/i2s/master.rs b/esp-hal/src/i2s/master.rs index 5da9e95ce26..95a33d62399 100644 --- a/esp-hal/src/i2s/master.rs +++ b/esp-hal/src/i2s/master.rs @@ -50,11 +50,11 @@ //! rx_descriptors, //! tx_descriptors, //! ); -#![cfg_attr(not(esp32), doc = "let i2s = i2s.with_mclk(peripherals.pins.gpio0);")] +#![cfg_attr(not(esp32), doc = "let i2s = i2s.with_mclk(peripherals.GPIO0);")] //! let mut i2s_rx = i2s.i2s_rx -//! .with_bclk(peripherals.pins.gpio1) -//! .with_ws(peripherals.pins.gpio2) -//! .with_din(peripherals.pins.gpio5) +//! .with_bclk(peripherals.GPIO1) +//! .with_ws(peripherals.GPIO2) +//! .with_din(peripherals.GPIO5) //! .build(); //! //! let mut transfer = i2s_rx.read_dma_circular(&mut rx_buffer).unwrap(); diff --git a/esp-hal/src/lcd_cam/cam.rs b/esp-hal/src/lcd_cam/cam.rs index 905c8d47d0b..5125d8b343d 100644 --- a/esp-hal/src/lcd_cam/cam.rs +++ b/esp-hal/src/lcd_cam/cam.rs @@ -31,19 +31,19 @@ //! # DmaPriority::Priority0, //! # ); //! -//! let mclk_pin = peripherals.pins.gpio15; -//! let vsync_pin = peripherals.pins.gpio6; -//! let href_pin = peripherals.pins.gpio7; -//! let pclk_pin = peripherals.pins.gpio13; +//! let mclk_pin = peripherals.GPIO15; +//! let vsync_pin = peripherals.GPIO6; +//! let href_pin = peripherals.GPIO7; +//! let pclk_pin = peripherals.GPIO13; //! let data_pins = RxEightBits::new( -//! peripherals.pins.gpio11, -//! peripherals.pins.gpio9, -//! peripherals.pins.gpio8, -//! peripherals.pins.gpio10, -//! peripherals.pins.gpio12, -//! peripherals.pins.gpio18, -//! peripherals.pins.gpio17, -//! peripherals.pins.gpio16, +//! peripherals.GPIO11, +//! peripherals.GPIO9, +//! peripherals.GPIO8, +//! peripherals.GPIO10, +//! peripherals.GPIO12, +//! peripherals.GPIO18, +//! peripherals.GPIO17, +//! peripherals.GPIO16, //! ); //! //! let lcd_cam = LcdCam::new(peripherals.LCD_CAM); diff --git a/esp-hal/src/lcd_cam/lcd/i8080.rs b/esp-hal/src/lcd_cam/lcd/i8080.rs index ce4b9e2e6b4..109b658aa39 100644 --- a/esp-hal/src/lcd_cam/lcd/i8080.rs +++ b/esp-hal/src/lcd_cam/lcd/i8080.rs @@ -30,14 +30,14 @@ //! # ); //! //! let tx_pins = TxEightBits::new( -//! peripherals.pins.gpio9, -//! peripherals.pins.gpio46, -//! peripherals.pins.gpio3, -//! peripherals.pins.gpio8, -//! peripherals.pins.gpio18, -//! peripherals.pins.gpio17, -//! peripherals.pins.gpio16, -//! peripherals.pins.gpio15, +//! peripherals.GPIO9, +//! peripherals.GPIO46, +//! peripherals.GPIO3, +//! peripherals.GPIO8, +//! peripherals.GPIO18, +//! peripherals.GPIO17, +//! peripherals.GPIO16, +//! peripherals.GPIO15, //! ); //! let lcd_cam = LcdCam::new(peripherals.LCD_CAM); //! @@ -48,7 +48,7 @@ //! 20.MHz(), //! Config::default(), //! ) -//! .with_ctrl_pins(peripherals.pins.gpio0, peripherals.pins.gpio47); +//! .with_ctrl_pins(peripherals.GPIO0, peripherals.GPIO47); //! //! dma_buf.fill(&[0x55]); //! let transfer = i8080.send(0x3Au8, 0, dma_buf).unwrap(); // RGB565 diff --git a/esp-hal/src/ledc/mod.rs b/esp-hal/src/ledc/mod.rs index fe414ff5677..54797a42880 100644 --- a/esp-hal/src/ledc/mod.rs +++ b/esp-hal/src/ledc/mod.rs @@ -29,7 +29,7 @@ //! # use esp_hal::ledc::timer; //! # use esp_hal::ledc::LowSpeed; //! # use esp_hal::ledc::channel; -//! # let led = peripherals.pins.gpio0; +//! # let led = peripherals.GPIO0; //! //! let mut ledc = Ledc::new(peripherals.LEDC); //! ledc.set_global_slow_clock(LSGlobalClkSource::APBClk); diff --git a/esp-hal/src/lib.rs b/esp-hal/src/lib.rs index ff938a3907a..21e2c6cd0cc 100644 --- a/esp-hal/src/lib.rs +++ b/esp-hal/src/lib.rs @@ -81,7 +81,7 @@ //! }); //! //! // Set GPIO0 as an output, and set its state high initially. -//! let mut led = Output::new(peripherals.pins.gpio0, Level::High); +//! let mut led = Output::new(peripherals.GPIO0, Level::High); //! //! let delay = Delay::new(); //! diff --git a/esp-hal/src/mcpwm/mod.rs b/esp-hal/src/mcpwm/mod.rs index 8f53ea33e66..dc981794a96 100644 --- a/esp-hal/src/mcpwm/mod.rs +++ b/esp-hal/src/mcpwm/mod.rs @@ -52,7 +52,7 @@ //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::mcpwm::{operator::{DeadTimeCfg, PWMStream, PwmPinConfig}, timer::PwmWorkingMode, McPwm, PeripheralClockConfig}; -//! # let pin = peripherals.pins.gpio0; +//! # let pin = peripherals.GPIO0; //! //! // initialize peripheral #![cfg_attr( diff --git a/esp-hal/src/mcpwm/operator.rs b/esp-hal/src/mcpwm/operator.rs index 1b580b72d60..51a8d0349b8 100644 --- a/esp-hal/src/mcpwm/operator.rs +++ b/esp-hal/src/mcpwm/operator.rs @@ -495,9 +495,9 @@ impl embedded_hal::pwm::SetD /// let mut mcpwm = McPwm::new(peripherals.MCPWM0, clock_cfg); /// /// let mut pins = mcpwm.operator0.with_linked_pins( -/// peripherals.pins.gpio0, +/// peripherals.GPIO0, /// PwmPinConfig::UP_DOWN_ACTIVE_HIGH, // use PWMA as our main input -/// peripherals.pins.gpio1, +/// peripherals.GPIO1, /// PwmPinConfig::EMPTY, // keep PWMB "low" /// bridge_off, /// ); diff --git a/esp-hal/src/peripheral.rs b/esp-hal/src/peripheral.rs index 19639c72b92..b8331ef68cc 100644 --- a/esp-hal/src/peripheral.rs +++ b/esp-hal/src/peripheral.rs @@ -121,14 +121,14 @@ impl DerefMut for PeripheralRef<'_, T> { /// live forever (`'static`): /// /// ```rust, ignore -/// let mut uart: Uart<'static, ...> = Uart::new(p.UART0, pins.gpio0, pins.gpio1); +/// let mut uart: Uart<'static, ...> = Uart::new(p.UART0, p.GPIO0, p.GPIO1); /// ``` /// /// Or you may call it with borrowed peripherals, which yields an instance that /// can only live for as long as the borrows last: /// /// ```rust, ignore -/// let mut uart: Uart<'_, ...> = Uart::new(&mut p.UART0, &mut pins.gpio0, &mut pins.gpio1); +/// let mut uart: Uart<'_, ...> = Uart::new(&mut p.UART0, &mut p.GPIO0, &mut p.GPIO1); /// ``` /// /// # Implementation details, for HAL authors @@ -222,9 +222,14 @@ mod peripheral_macros { #[macro_export] macro_rules! peripherals { ( - $( - $name:ident <= $from_pac:tt $(($($interrupt:ident),*))? - ), *$(,)? + peripherals: [ + $( + $name:ident <= $from_pac:tt $(($($interrupt:ident),*))? + ), *$(,)? + ], + pins: [ + $( ( $pin:literal, $($pin_tokens:tt)* ) )* + ] ) => { /// Contains the generated peripherals which implement [`Peripheral`] @@ -235,45 +240,59 @@ mod peripheral_macros { )* } - /// The `Peripherals` struct provides access to all of the hardware peripherals on the chip. - #[allow(non_snake_case)] - pub struct Peripherals { - $( - /// Each field represents a hardware peripheral. - pub $name: peripherals::$name, - )* - /// The pins available on this chip - pub pins: $crate::gpio::Pins, + pub(crate) mod gpio { + crate::gpio! { + $( ($pin, $($pin_tokens)* ) )* + } } - impl Peripherals { - /// Returns all the peripherals *once* - #[inline] - pub(crate) fn take() -> Self { - #[no_mangle] - static mut _ESP_HAL_DEVICE_PERIPHERALS: bool = false; - - critical_section::with(|_| unsafe { - if _ESP_HAL_DEVICE_PERIPHERALS { - panic!("init called more than once!") - } - _ESP_HAL_DEVICE_PERIPHERALS = true; - Self::steal() - }) + paste::paste! { + /// The `Peripherals` struct provides access to all of the hardware peripherals on the chip. + #[allow(non_snake_case)] + pub struct Peripherals { + $( + #[doc = concat!("The ", stringify!($name), " peripheral.")] + pub $name: peripherals::$name, + )* + + $( + #[doc = concat!("GPIO", stringify!($pin))] + pub []: crate::gpio::GpioPin<$pin>, + )* } - /// 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 { - $( - $name: peripherals::$name::steal(), - )* - pins: $crate::gpio::Pins::steal(), + impl Peripherals { + /// Returns all the peripherals *once* + #[inline] + pub(crate) fn take() -> Self { + #[no_mangle] + static mut _ESP_HAL_DEVICE_PERIPHERALS: bool = false; + + critical_section::with(|_| unsafe { + if _ESP_HAL_DEVICE_PERIPHERALS { + panic!("init called more than once!") + } + _ESP_HAL_DEVICE_PERIPHERALS = true; + Self::steal() + }) + } + + /// 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 { + $( + $name: peripherals::$name::steal(), + )* + + $( + []: crate::gpio::GpioPin::<$pin>::steal(), + )* + } } } } @@ -297,8 +316,7 @@ mod peripheral_macros { } )* )* - - } + }; } #[doc(hidden)] diff --git a/esp-hal/src/rmt.rs b/esp-hal/src/rmt.rs index 67949ea1341..ef6f4b1063a 100644 --- a/esp-hal/src/rmt.rs +++ b/esp-hal/src/rmt.rs @@ -61,7 +61,7 @@ //! let mut channel = rmt //! .channel0 //! .configure( -//! peripherals.pins.gpio1, +//! peripherals.GPIO1, //! TxChannelConfig { //! clk_divider: 1, //! idle_output_level: false, diff --git a/esp-hal/src/rng.rs b/esp-hal/src/rng.rs index d9666e300e3..6266b9fddc9 100644 --- a/esp-hal/src/rng.rs +++ b/esp-hal/src/rng.rs @@ -147,8 +147,8 @@ impl rand_core::RngCore for Rng { /// let mut true_rand = trng.random(); /// let mut rng = trng.downgrade(); /// // ADC is available now -#[cfg_attr(esp32, doc = "let analog_pin = peripherals.pins.gpio32;")] -#[cfg_attr(not(esp32), doc = "let analog_pin = peripherals.pins.gpio3;")] +#[cfg_attr(esp32, doc = "let analog_pin = peripherals.GPIO32;")] +#[cfg_attr(not(esp32), doc = "let analog_pin = peripherals.GPIO3;")] /// let mut adc1_config = AdcConfig::new(); /// let mut adc1_pin = adc1_config.enable_pin( /// analog_pin, diff --git a/esp-hal/src/rom/md5.rs b/esp-hal/src/rom/md5.rs index 2c249e226df..1eb3e9a7480 100644 --- a/esp-hal/src/rom/md5.rs +++ b/esp-hal/src/rom/md5.rs @@ -34,7 +34,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let mut uart0 = Uart::new(peripherals.UART0, peripherals.pins.gpio1, peripherals.pins.gpio2).unwrap(); +//! # let mut uart0 = Uart::new(peripherals.UART0, peripherals.GPIO1, peripherals.GPIO2).unwrap(); //! # let data = "Dummy"; //! let d: md5::Digest = md5::compute(&data); //! writeln!(uart0, "{}", d); @@ -48,7 +48,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let mut uart0 = Uart::new(peripherals.UART0, peripherals.pins.gpio1, peripherals.pins.gpio2).unwrap(); +//! # let mut uart0 = Uart::new(peripherals.UART0, peripherals.GPIO1, peripherals.GPIO2).unwrap(); //! # let data0 = "Dummy"; //! # let data1 = "Dummy"; //! # diff --git a/esp-hal/src/rtc_cntl/sleep/esp32c6.rs b/esp-hal/src/rtc_cntl/sleep/esp32c6.rs index 19e737c487c..4692513c992 100644 --- a/esp-hal/src/rtc_cntl/sleep/esp32c6.rs +++ b/esp-hal/src/rtc_cntl/sleep/esp32c6.rs @@ -3,7 +3,7 @@ use core::ops::Not; use crate::{ clock::Clock, efuse::Efuse, - gpio::{Pins, RtcFunction}, + gpio::RtcFunction, rtc_cntl::{ rtc::{ rtc_clk_cpu_freq_set_xtal, @@ -71,10 +71,10 @@ impl Ext1WakeupSource<'_, '_> { unsafe { lp_aon().ext_wakeup_cntl().read().ext_wakeup_sel().bits() } } - fn wake_io_reset(pins: &mut Pins) { - use crate::gpio::RtcPin; + fn wake_io_reset() { + use crate::gpio::{GpioPin, RtcPin}; - fn uninit_pin(pin: &mut impl RtcPin, wakeup_pins: u8) { + fn uninit_pin(mut pin: impl RtcPin, wakeup_pins: u8) { if wakeup_pins & (1 << pin.number()) != 0 { pin.rtcio_pad_hold(false); pin.rtc_set_config(false, false, RtcFunction::Rtc); @@ -82,14 +82,14 @@ impl Ext1WakeupSource<'_, '_> { } let wakeup_pins = Ext1WakeupSource::wakeup_pins(); - uninit_pin(&mut pins.gpio0, wakeup_pins); - uninit_pin(&mut pins.gpio1, wakeup_pins); - uninit_pin(&mut pins.gpio2, wakeup_pins); - uninit_pin(&mut pins.gpio3, wakeup_pins); - uninit_pin(&mut pins.gpio4, wakeup_pins); - uninit_pin(&mut pins.gpio5, wakeup_pins); - uninit_pin(&mut pins.gpio6, wakeup_pins); - uninit_pin(&mut pins.gpio7, wakeup_pins); + uninit_pin(unsafe { GpioPin::<0>::steal() }, wakeup_pins); + uninit_pin(unsafe { GpioPin::<1>::steal() }, wakeup_pins); + uninit_pin(unsafe { GpioPin::<2>::steal() }, wakeup_pins); + uninit_pin(unsafe { GpioPin::<3>::steal() }, wakeup_pins); + uninit_pin(unsafe { GpioPin::<4>::steal() }, wakeup_pins); + uninit_pin(unsafe { GpioPin::<5>::steal() }, wakeup_pins); + uninit_pin(unsafe { GpioPin::<6>::steal() }, wakeup_pins); + uninit_pin(unsafe { GpioPin::<7>::steal() }, wakeup_pins); } } @@ -898,15 +898,7 @@ impl RtcSleepConfig { fn wake_io_reset() { // loosely based on esp_deep_sleep_wakeup_io_reset - - let mut pins = unsafe { - // We're stealing pins to do some uninitialization after waking up from - // deep sleep. We have to be careful to only touch settings that were enabled - // by deep sleep setup. - Pins::steal() - }; - - Ext1WakeupSource::wake_io_reset(&mut pins); + Ext1WakeupSource::wake_io_reset(); } /// Finalize power-down flags, apply configuration based on the flags. diff --git a/esp-hal/src/soc/esp32/efuse/mod.rs b/esp-hal/src/soc/esp32/efuse/mod.rs index 1ffb4263002..ff59b537f9e 100644 --- a/esp-hal/src/soc/esp32/efuse/mod.rs +++ b/esp-hal/src/soc/esp32/efuse/mod.rs @@ -27,7 +27,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.pins.gpio4, peripherals.pins.gpio5).unwrap(); +//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.GPIO4, peripherals.GPIO5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32/gpio.rs b/esp-hal/src/soc/esp32/gpio.rs index b2e34a52ff3..9a7f8449fff 100644 --- a/esp-hal/src/soc/esp32/gpio.rs +++ b/esp-hal/src/soc/esp32/gpio.rs @@ -536,7 +536,7 @@ macro_rules! rtcio_analog { ( $pin_num:expr, $rtc_pin:expr, $pin_reg:expr, $prefix:pat, $hold:ident $(, $rue:literal)? ) => { - impl $crate::gpio::RtcPin for GpioPin<$pin_num> { + impl $crate::gpio::RtcPin for $crate::gpio::GpioPin<$pin_num> { fn rtc_number(&self) -> u8 { $rtc_pin } @@ -565,7 +565,7 @@ macro_rules! rtcio_analog { $( // FIXME: replace with $(ignore($rue)) once stable rtcio_analog!(@ignore $rue); - impl $crate::gpio::RtcPinWithResistors for GpioPin<$pin_num> { + impl $crate::gpio::RtcPinWithResistors for $crate::gpio::GpioPin<$pin_num> { fn rtcio_pullup(&mut self, enable: bool) { paste::paste! { unsafe { $crate::peripherals::RTC_IO::steal() } @@ -582,7 +582,7 @@ macro_rules! rtcio_analog { } )? - impl $crate::gpio::AnalogPin for GpioPin<$pin_num> { + impl $crate::gpio::AnalogPin for $crate::gpio::GpioPin<$pin_num> { /// Configures the pin for analog mode. fn set_analog(&self, _: $crate::private::Internal) { use $crate::gpio::RtcPin; @@ -629,7 +629,7 @@ macro_rules! rtcio_analog { rtcio_analog!($pin_num, $rtc_pin, $pin_reg, $prefix, $hold $(, $rue )?); )+ - pub(crate) fn errata36(mut pin: AnyPin, pull_up: bool, pull_down: bool) { + pub(crate) fn errata36(mut pin: $crate::gpio::AnyPin, pull_up: bool, pull_down: bool) { use $crate::gpio::{Pin, RtcPinWithResistors}; let has_pullups = match pin.number() { @@ -744,45 +744,6 @@ macro_rules! touch { }; } -crate::gpio! { - (0, [Input, Output, Analog, RtcIo, Touch] (5 => EMAC_TX_CLK) (1 => CLK_OUT1)) - (1, [Input, Output] (5 => EMAC_RXD2) (0 => U0TXD 1 => CLK_OUT3)) - (2, [Input, Output, Analog, RtcIo, Touch] (1 => HSPIWP 3 => HS2_DATA0 4 => SD_DATA0) (3 => HS2_DATA0 4 => SD_DATA0)) - (3, [Input, Output] (0 => U0RXD) (1 => CLK_OUT2)) - (4, [Input, Output, Analog, RtcIo, Touch] (1 => HSPIHD 3 => HS2_DATA1 4 => SD_DATA1 5 => EMAC_TX_ER) (3 => HS2_DATA1 4 => SD_DATA1)) - (5, [Input, Output] (1 => VSPICS0 3 => HS1_DATA6 5 => EMAC_RX_CLK) (3 => HS1_DATA6)) - (6, [Input, Output] (4 => U1CTS) (0 => SD_CLK 1 => SPICLK 3 => HS1_CLK)) - (7, [Input, Output] (0 => SD_DATA0 1 => SPIQ 3 => HS1_DATA0) (0 => SD_DATA0 1 => SPIQ 3 => HS1_DATA0 4 => U2RTS)) - (8, [Input, Output] (0 => SD_DATA1 1 => SPID 3 => HS1_DATA1 4 => U2CTS) (0 => SD_DATA1 1 => SPID 3 => HS1_DATA1)) - (9, [Input, Output] (0 => SD_DATA2 1 => SPIHD 3 => HS1_DATA2 4 => U1RXD) (0 => SD_DATA2 1 => SPIHD 3 => HS1_DATA2)) - (10, [Input, Output] ( 0 => SD_DATA3 1 => SPIWP 3 => HS1_DATA3) (0 => SD_DATA3 1 => SPIWP 3 => HS1_DATA3 4 => U1TXD)) - (11, [Input, Output] ( 1 => SPICS0) (0 => SD_CMD 1 => SPICS0 3 => HS1_CMD 4 => U1RTS)) - (12, [Input, Output, Analog, RtcIo, Touch] (0 => MTDI 1 => HSPIQ 3 => HS2_DATA2 4 => SD_DATA2) (1 => HSPIQ 3 => HS2_DATA2 4 => SD_DATA2 5 => EMAC_TXD3)) - (13, [Input, Output, Analog, RtcIo, Touch] (0 => MTCK 1 => HSPID 3 => HS2_DATA3 4 => SD_DATA3) (1 => HSPID 3 => HS2_DATA3 4 => SD_DATA3 5 => EMAC_RX_ER)) - (14, [Input, Output, Analog, RtcIo, Touch] (0 => MTMS 1 => HSPICLK) (1 => HSPICLK 3 => HS2_CLK 4 => SD_CLK 5 => EMAC_TXD2)) - (15, [Input, Output, Analog, RtcIo, Touch] (1 => HSPICS0 5 => EMAC_RXD3) (0 => MTDO 1 => HSPICS0 3 => HS2_CMD 4 => SD_CMD)) - (16, [Input, Output] (3 => HS1_DATA4 4 => U2RXD) (3 => HS1_DATA4 5 => EMAC_CLK_OUT)) - (17, [Input, Output] (3 => HS1_DATA5) (3 => HS1_DATA5 4 => U2TXD 5 => EMAC_CLK_180)) - (18, [Input, Output] (1 => VSPICLK 3 => HS1_DATA7) (1 => VSPICLK 3 => HS1_DATA7)) - (19, [Input, Output] (1 => VSPIQ 3 => U0CTS) (1 => VSPIQ 5 => EMAC_TXD0)) - (20, [Input, Output]) - (21, [Input, Output] (1 => VSPIHD) (1 => VSPIHD 5 => EMAC_TX_EN)) - (22, [Input, Output] (1 => VSPIWP) (1 => VSPIWP 3 => U0RTS 5 => EMAC_TXD1)) - (23, [Input, Output] (1 => VSPID) (1 => VSPID 3 => HS1_STROBE)) - (24, [Input, Output]) - (25, [Input, Output, Analog, RtcIo] (5 => EMAC_RXD0) ()) - (26, [Input, Output, Analog, RtcIo] (5 => EMAC_RXD1) ()) - (27, [Input, Output, Analog, RtcIo, Touch] (5 => EMAC_RX_DV) ()) - (32, [Input, Output, Analog, RtcIo, Touch]) - (33, [Input, Output, Analog, RtcIo, Touch]) - (34, [Input, Analog, RtcIoInput]) - (35, [Input, Analog, RtcIoInput]) - (36, [Input, Analog, RtcIoInput]) - (37, [Input, Analog, RtcIoInput]) - (38, [Input, Analog, RtcIoInput]) - (39, [Input, Analog, RtcIoInput]) -} - rtcio_analog! { (36, 0, sensor_pads(), sense1_, sense1_hold_force ) (37, 1, sensor_pads(), sense2_, sense2_hold_force ) diff --git a/esp-hal/src/soc/esp32/peripherals.rs b/esp-hal/src/soc/esp32/peripherals.rs index 172ff834cf9..2bfa72fc05e 100644 --- a/esp-hal/src/soc/esp32/peripherals.rs +++ b/esp-hal/src/soc/esp32/peripherals.rs @@ -20,57 +20,97 @@ pub(crate) use self::peripherals::*; // peripheral (no `PSRAM`, `RADIO`, etc. peripheral in the PACs), so we're // creating "virtual peripherals" for them. crate::peripherals! { - ADC1 <= virtual, - ADC2 <= virtual, - AES <= AES, - APB_CTRL <= APB_CTRL, - BB <= BB, - BT <= virtual, - CPU_CTRL <= virtual, - DAC1 <= virtual, - DAC2 <= virtual, - DMA <= virtual, - EFUSE <= EFUSE, - FLASH_ENCRYPTION <= FLASH_ENCRYPTION, - FRC_TIMER <= FRC_TIMER, - GPIO_SD <= GPIO_SD, - HINF <= HINF, - I2C0 <= I2C0, - I2C1 <= I2C1, - I2S0 <= I2S0 (I2S0), - I2S1 <= I2S1 (I2S1), - IO_MUX <= IO_MUX, - LEDC <= LEDC, - MCPWM0 <= MCPWM0, - MCPWM1 <= MCPWM1, - NRX <= NRX, - PCNT <= PCNT, - PSRAM <= virtual, - RMT <= RMT, - RNG <= RNG, - RSA <= RSA, - LPWR <= RTC_CNTL, - RADIO_CLK <= virtual, - RTC_IO <= RTC_IO, - RTC_I2C <= RTC_I2C, - SDHOST <= SDHOST, - SHA <= SHA, - SLC <= SLC, - SLCHOST <= SLCHOST, - SPI0 <= SPI0, - SPI1 <= SPI1, - SPI2 <= SPI2 (SPI2_DMA, SPI2), - SPI3 <= SPI3 (SPI3_DMA, SPI3), - SYSTEM <= DPORT, - SW_INTERRUPT <= virtual, - TIMG0 <= TIMG0, - TIMG1 <= TIMG1, - TOUCH <= virtual, - TWAI0 <= TWAI0, - UART0 <= UART0, - UART1 <= UART1, - UART2 <= UART2, - UHCI0 <= UHCI0, - UHCI1 <= UHCI1, - WIFI <= virtual, + peripherals: [ + ADC1 <= virtual, + ADC2 <= virtual, + AES <= AES, + APB_CTRL <= APB_CTRL, + BB <= BB, + BT <= virtual, + CPU_CTRL <= virtual, + DAC1 <= virtual, + DAC2 <= virtual, + DMA <= virtual, + EFUSE <= EFUSE, + FLASH_ENCRYPTION <= FLASH_ENCRYPTION, + FRC_TIMER <= FRC_TIMER, + GPIO_SD <= GPIO_SD, + HINF <= HINF, + I2C0 <= I2C0, + I2C1 <= I2C1, + I2S0 <= I2S0 (I2S0), + I2S1 <= I2S1 (I2S1), + IO_MUX <= IO_MUX, + LEDC <= LEDC, + MCPWM0 <= MCPWM0, + MCPWM1 <= MCPWM1, + NRX <= NRX, + PCNT <= PCNT, + PSRAM <= virtual, + RMT <= RMT, + RNG <= RNG, + RSA <= RSA, + LPWR <= RTC_CNTL, + RADIO_CLK <= virtual, + RTC_IO <= RTC_IO, + RTC_I2C <= RTC_I2C, + SDHOST <= SDHOST, + SHA <= SHA, + SLC <= SLC, + SLCHOST <= SLCHOST, + SPI0 <= SPI0, + SPI1 <= SPI1, + SPI2 <= SPI2 (SPI2_DMA, SPI2), + SPI3 <= SPI3 (SPI3_DMA, SPI3), + SYSTEM <= DPORT, + SW_INTERRUPT <= virtual, + TIMG0 <= TIMG0, + TIMG1 <= TIMG1, + TOUCH <= virtual, + TWAI0 <= TWAI0, + UART0 <= UART0, + UART1 <= UART1, + UART2 <= UART2, + UHCI0 <= UHCI0, + UHCI1 <= UHCI1, + WIFI <= virtual, + ], + pins: [ + (0, [Input, Output, Analog, RtcIo, Touch] (5 => EMAC_TX_CLK) (1 => CLK_OUT1)) + (1, [Input, Output] (5 => EMAC_RXD2) (0 => U0TXD 1 => CLK_OUT3)) + (2, [Input, Output, Analog, RtcIo, Touch] (1 => HSPIWP 3 => HS2_DATA0 4 => SD_DATA0) (3 => HS2_DATA0 4 => SD_DATA0)) + (3, [Input, Output] (0 => U0RXD) (1 => CLK_OUT2)) + (4, [Input, Output, Analog, RtcIo, Touch] (1 => HSPIHD 3 => HS2_DATA1 4 => SD_DATA1 5 => EMAC_TX_ER) (3 => HS2_DATA1 4 => SD_DATA1)) + (5, [Input, Output] (1 => VSPICS0 3 => HS1_DATA6 5 => EMAC_RX_CLK) (3 => HS1_DATA6)) + (6, [Input, Output] (4 => U1CTS) (0 => SD_CLK 1 => SPICLK 3 => HS1_CLK)) + (7, [Input, Output] (0 => SD_DATA0 1 => SPIQ 3 => HS1_DATA0) (0 => SD_DATA0 1 => SPIQ 3 => HS1_DATA0 4 => U2RTS)) + (8, [Input, Output] (0 => SD_DATA1 1 => SPID 3 => HS1_DATA1 4 => U2CTS) (0 => SD_DATA1 1 => SPID 3 => HS1_DATA1)) + (9, [Input, Output] (0 => SD_DATA2 1 => SPIHD 3 => HS1_DATA2 4 => U1RXD) (0 => SD_DATA2 1 => SPIHD 3 => HS1_DATA2)) + (10, [Input, Output] ( 0 => SD_DATA3 1 => SPIWP 3 => HS1_DATA3) (0 => SD_DATA3 1 => SPIWP 3 => HS1_DATA3 4 => U1TXD)) + (11, [Input, Output] ( 1 => SPICS0) (0 => SD_CMD 1 => SPICS0 3 => HS1_CMD 4 => U1RTS)) + (12, [Input, Output, Analog, RtcIo, Touch] (0 => MTDI 1 => HSPIQ 3 => HS2_DATA2 4 => SD_DATA2) (1 => HSPIQ 3 => HS2_DATA2 4 => SD_DATA2 5 => EMAC_TXD3)) + (13, [Input, Output, Analog, RtcIo, Touch] (0 => MTCK 1 => HSPID 3 => HS2_DATA3 4 => SD_DATA3) (1 => HSPID 3 => HS2_DATA3 4 => SD_DATA3 5 => EMAC_RX_ER)) + (14, [Input, Output, Analog, RtcIo, Touch] (0 => MTMS 1 => HSPICLK) (1 => HSPICLK 3 => HS2_CLK 4 => SD_CLK 5 => EMAC_TXD2)) + (15, [Input, Output, Analog, RtcIo, Touch] (1 => HSPICS0 5 => EMAC_RXD3) (0 => MTDO 1 => HSPICS0 3 => HS2_CMD 4 => SD_CMD)) + (16, [Input, Output] (3 => HS1_DATA4 4 => U2RXD) (3 => HS1_DATA4 5 => EMAC_CLK_OUT)) + (17, [Input, Output] (3 => HS1_DATA5) (3 => HS1_DATA5 4 => U2TXD 5 => EMAC_CLK_180)) + (18, [Input, Output] (1 => VSPICLK 3 => HS1_DATA7) (1 => VSPICLK 3 => HS1_DATA7)) + (19, [Input, Output] (1 => VSPIQ 3 => U0CTS) (1 => VSPIQ 5 => EMAC_TXD0)) + (20, [Input, Output]) + (21, [Input, Output] (1 => VSPIHD) (1 => VSPIHD 5 => EMAC_TX_EN)) + (22, [Input, Output] (1 => VSPIWP) (1 => VSPIWP 3 => U0RTS 5 => EMAC_TXD1)) + (23, [Input, Output] (1 => VSPID) (1 => VSPID 3 => HS1_STROBE)) + (24, [Input, Output]) + (25, [Input, Output, Analog, RtcIo] (5 => EMAC_RXD0) ()) + (26, [Input, Output, Analog, RtcIo] (5 => EMAC_RXD1) ()) + (27, [Input, Output, Analog, RtcIo, Touch] (5 => EMAC_RX_DV) ()) + (32, [Input, Output, Analog, RtcIo, Touch]) + (33, [Input, Output, Analog, RtcIo, Touch]) + (34, [Input, Analog, RtcIoInput]) + (35, [Input, Analog, RtcIoInput]) + (36, [Input, Analog, RtcIoInput]) + (37, [Input, Analog, RtcIoInput]) + (38, [Input, Analog, RtcIoInput]) + (39, [Input, Analog, RtcIoInput]) + ] } diff --git a/esp-hal/src/soc/esp32c2/efuse/mod.rs b/esp-hal/src/soc/esp32c2/efuse/mod.rs index 83c5f116763..bfd724fd459 100644 --- a/esp-hal/src/soc/esp32c2/efuse/mod.rs +++ b/esp-hal/src/soc/esp32c2/efuse/mod.rs @@ -24,7 +24,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.pins.gpio4, peripherals.pins.gpio5).unwrap(); +//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.GPIO4, peripherals.GPIO5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32c2/gpio.rs b/esp-hal/src/soc/esp32c2/gpio.rs index 5304cc66c1b..f7080686beb 100644 --- a/esp-hal/src/soc/esp32c2/gpio.rs +++ b/esp-hal/src/soc/esp32c2/gpio.rs @@ -215,23 +215,6 @@ where } } -crate::gpio! { - (0, [Input, Output, Analog, RtcIo]) - (1, [Input, Output, Analog, RtcIo]) - (2, [Input, Output, Analog, RtcIo] (2 => FSPIQ) (2 => FSPIQ)) - (3, [Input, Output, Analog, RtcIo]) - (4, [Input, Output, Analog, RtcIo] (2 => FSPIHD) (2 => FSPIHD)) - (5, [Input, Output, Analog, RtcIo] (2 => FSPIWP) (2 => FSPIWP)) - (6, [Input, Output] (2 => FSPICLK) (2 => FSPICLK_MUX)) - (7, [Input, Output] (2 => FSPID) (2 => FSPID)) - (8, [Input, Output]) - (9, [Input, Output]) - (10, [Input, Output] (2 => FSPICS0) (2 => FSPICS0)) - (18, [Input, Output]) - (19, [Input, Output]) - (20, [Input, Output] (0 => U0RXD) ()) -} - rtc_pins! { 0 1 diff --git a/esp-hal/src/soc/esp32c2/peripherals.rs b/esp-hal/src/soc/esp32c2/peripherals.rs index 4685a536c21..6748f4e6ce5 100644 --- a/esp-hal/src/soc/esp32c2/peripherals.rs +++ b/esp-hal/src/soc/esp32c2/peripherals.rs @@ -20,39 +20,57 @@ pub(crate) use self::peripherals::*; // peripheral (no `PSRAM`, `RADIO`, etc. peripheral in the PACs), so we're // creating "virtual peripherals" for them. crate::peripherals! { - ADC1 <= virtual, - APB_CTRL <= APB_CTRL, - ASSIST_DEBUG <= ASSIST_DEBUG, - BT <= virtual, - DMA <= DMA (DMA_CH0), - ECC <= ECC, - EFUSE <= EFUSE, - EXTMEM <= EXTMEM, - I2C0 <= I2C0, - INTERRUPT_CORE0 <= INTERRUPT_CORE0, - IO_MUX <= IO_MUX, - LEDC <= LEDC, - LPWR <= RTC_CNTL, - RADIO_CLK <= virtual, - RNG <= RNG, - SENSITIVE <= SENSITIVE, - SHA <= SHA, - SPI0 <= SPI0, - SPI1 <= SPI1, - SPI2 <= SPI2 (SPI2), - SYSTEM <= SYSTEM, - SYSTIMER <= SYSTIMER, - SW_INTERRUPT <= virtual, - TIMG0 <= TIMG0, - UART0 <= UART0, - UART1 <= UART1, - WIFI <= virtual, - XTS_AES <= XTS_AES, - MEM2MEM1 <= virtual, - MEM2MEM2 <= virtual, - MEM2MEM3 <= virtual, - MEM2MEM4 <= virtual, - MEM2MEM5 <= virtual, - MEM2MEM6 <= virtual, - MEM2MEM8 <= virtual, + peripherals: [ + ADC1 <= virtual, + APB_CTRL <= APB_CTRL, + ASSIST_DEBUG <= ASSIST_DEBUG, + BT <= virtual, + DMA <= DMA (DMA_CH0), + ECC <= ECC, + EFUSE <= EFUSE, + EXTMEM <= EXTMEM, + I2C0 <= I2C0, + INTERRUPT_CORE0 <= INTERRUPT_CORE0, + IO_MUX <= IO_MUX, + LEDC <= LEDC, + LPWR <= RTC_CNTL, + RADIO_CLK <= virtual, + RNG <= RNG, + SENSITIVE <= SENSITIVE, + SHA <= SHA, + SPI0 <= SPI0, + SPI1 <= SPI1, + SPI2 <= SPI2 (SPI2), + SYSTEM <= SYSTEM, + SYSTIMER <= SYSTIMER, + SW_INTERRUPT <= virtual, + TIMG0 <= TIMG0, + UART0 <= UART0, + UART1 <= UART1, + WIFI <= virtual, + XTS_AES <= XTS_AES, + MEM2MEM1 <= virtual, + MEM2MEM2 <= virtual, + MEM2MEM3 <= virtual, + MEM2MEM4 <= virtual, + MEM2MEM5 <= virtual, + MEM2MEM6 <= virtual, + MEM2MEM8 <= virtual, + ], + pins: [ + (0, [Input, Output, Analog, RtcIo]) + (1, [Input, Output, Analog, RtcIo]) + (2, [Input, Output, Analog, RtcIo] (2 => FSPIQ) (2 => FSPIQ)) + (3, [Input, Output, Analog, RtcIo]) + (4, [Input, Output, Analog, RtcIo] (2 => FSPIHD) (2 => FSPIHD)) + (5, [Input, Output, Analog, RtcIo] (2 => FSPIWP) (2 => FSPIWP)) + (6, [Input, Output] (2 => FSPICLK) (2 => FSPICLK_MUX)) + (7, [Input, Output] (2 => FSPID) (2 => FSPID)) + (8, [Input, Output]) + (9, [Input, Output]) + (10, [Input, Output] (2 => FSPICS0) (2 => FSPICS0)) + (18, [Input, Output]) + (19, [Input, Output]) + (20, [Input, Output] (0 => U0RXD) ()) + ] } diff --git a/esp-hal/src/soc/esp32c3/efuse/mod.rs b/esp-hal/src/soc/esp32c3/efuse/mod.rs index 5d4f4d7fc7c..c7fae51caab 100644 --- a/esp-hal/src/soc/esp32c3/efuse/mod.rs +++ b/esp-hal/src/soc/esp32c3/efuse/mod.rs @@ -25,7 +25,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.pins.gpio4, peripherals.pins.gpio5).unwrap(); +//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.GPIO4, peripherals.GPIO5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32c3/gpio.rs b/esp-hal/src/soc/esp32c3/gpio.rs index 80af84bb36f..f6a4fd76fcb 100644 --- a/esp-hal/src/soc/esp32c3/gpio.rs +++ b/esp-hal/src/soc/esp32c3/gpio.rs @@ -243,31 +243,6 @@ where } } -crate::gpio! { - (0, [Input, Output, Analog, RtcIo]) - (1, [Input, Output, Analog, RtcIo]) - (2, [Input, Output, Analog, RtcIo] (2 => FSPIQ) (2 => FSPIQ)) - (3, [Input, Output, Analog, RtcIo]) - (4, [Input, Output, Analog, RtcIo] (2 => FSPIHD) (0 => USB_JTAG_TMS 2 => FSPIHD)) - (5, [Input, Output, Analog, RtcIo] (2 => FSPIWP) (0 => USB_JTAG_TDI 2 => FSPIWP)) - (6, [Input, Output] (2 => FSPICLK) (0 => USB_JTAG_TCK 2 => FSPICLK_MUX)) - (7, [Input, Output] (2 => FSPID) (0 => USB_JTAG_TDO 2 => FSPID)) - (8, [Input, Output]) - (9, [Input, Output]) - (10, [Input, Output] (2 => FSPICS0) (2 => FSPICS0)) - (11, [Input, Output]) - (12, [Input, Output] (0 => SPIHD) (0 => SPIHD)) - (13, [Input, Output] (0 => SPIWP) (0 => SPIWP)) - (14, [Input, Output] () (0 => SPICS0)) - (15, [Input, Output] () (0 => SPICLK_MUX)) - (16, [Input, Output] (0 => SPID) (0 => SPID)) - (17, [Input, Output] (0 => SPIQ) (0 => SPIQ)) - (18, [Input, Output]) - (19, [Input, Output]) - (20, [Input, Output] (0 => U0RXD) ()) - (21, [Input, Output] () (0 => U0TXD)) -} - // RTC pins 0 through 5 (inclusive) support GPIO wakeup rtc_pins! { 0 diff --git a/esp-hal/src/soc/esp32c3/peripherals.rs b/esp-hal/src/soc/esp32c3/peripherals.rs index 611a3f13f8a..f4a52d4fc08 100644 --- a/esp-hal/src/soc/esp32c3/peripherals.rs +++ b/esp-hal/src/soc/esp32c3/peripherals.rs @@ -20,44 +20,70 @@ pub(crate) use self::peripherals::*; // peripheral (no `PSRAM`, `RADIO`, etc. peripheral in the PACs), so we're // creating "virtual peripherals" for them. crate::peripherals! { - ADC1 <= virtual, - ADC2 <= virtual, - AES <= AES, - APB_CTRL <= APB_CTRL, - ASSIST_DEBUG <= ASSIST_DEBUG, - BT <= virtual, - DMA <= DMA (DMA_CH0,DMA_CH1,DMA_CH2), - DS <= DS, - EFUSE <= EFUSE, - EXTMEM <= EXTMEM, - GPIO_SD <= GPIO_SD, - HMAC <= HMAC, - I2C0 <= I2C0, - I2S0 <= I2S0 (I2S0), - INTERRUPT_CORE0 <= INTERRUPT_CORE0, - IO_MUX <= IO_MUX, - LEDC <= LEDC, - LPWR <= RTC_CNTL, - RADIO_CLK <= virtual, - RMT <= RMT, - RNG <= RNG, - RSA <= RSA, - SENSITIVE <= SENSITIVE, - SHA <= SHA, - SPI0 <= SPI0, - SPI1 <= SPI1, - SPI2 <= SPI2 (SPI2), - SYSTEM <= SYSTEM, - SYSTIMER <= SYSTIMER, - SW_INTERRUPT <= virtual, - TIMG0 <= TIMG0, - TIMG1 <= TIMG1, - TWAI0 <= TWAI0, - UART0 <= UART0, - UART1 <= UART1, - UHCI0 <= UHCI0, - UHCI1 <= UHCI1, - USB_DEVICE <= USB_DEVICE, - WIFI <= virtual, - XTS_AES <= XTS_AES, + peripherals: [ + ADC1 <= virtual, + ADC2 <= virtual, + AES <= AES, + APB_CTRL <= APB_CTRL, + ASSIST_DEBUG <= ASSIST_DEBUG, + BT <= virtual, + DMA <= DMA (DMA_CH0,DMA_CH1,DMA_CH2), + DS <= DS, + EFUSE <= EFUSE, + EXTMEM <= EXTMEM, + GPIO_SD <= GPIO_SD, + HMAC <= HMAC, + I2C0 <= I2C0, + I2S0 <= I2S0 (I2S0), + INTERRUPT_CORE0 <= INTERRUPT_CORE0, + IO_MUX <= IO_MUX, + LEDC <= LEDC, + LPWR <= RTC_CNTL, + RADIO_CLK <= virtual, + RMT <= RMT, + RNG <= RNG, + RSA <= RSA, + SENSITIVE <= SENSITIVE, + SHA <= SHA, + SPI0 <= SPI0, + SPI1 <= SPI1, + SPI2 <= SPI2 (SPI2), + SYSTEM <= SYSTEM, + SYSTIMER <= SYSTIMER, + SW_INTERRUPT <= virtual, + TIMG0 <= TIMG0, + TIMG1 <= TIMG1, + TWAI0 <= TWAI0, + UART0 <= UART0, + UART1 <= UART1, + UHCI0 <= UHCI0, + UHCI1 <= UHCI1, + USB_DEVICE <= USB_DEVICE, + WIFI <= virtual, + XTS_AES <= XTS_AES, + ], + pins: [ + (0, [Input, Output, Analog, RtcIo]) + (1, [Input, Output, Analog, RtcIo]) + (2, [Input, Output, Analog, RtcIo] (2 => FSPIQ) (2 => FSPIQ)) + (3, [Input, Output, Analog, RtcIo]) + (4, [Input, Output, Analog, RtcIo] (2 => FSPIHD) (0 => USB_JTAG_TMS 2 => FSPIHD)) + (5, [Input, Output, Analog, RtcIo] (2 => FSPIWP) (0 => USB_JTAG_TDI 2 => FSPIWP)) + (6, [Input, Output] (2 => FSPICLK) (0 => USB_JTAG_TCK 2 => FSPICLK_MUX)) + (7, [Input, Output] (2 => FSPID) (0 => USB_JTAG_TDO 2 => FSPID)) + (8, [Input, Output]) + (9, [Input, Output]) + (10, [Input, Output] (2 => FSPICS0) (2 => FSPICS0)) + (11, [Input, Output]) + (12, [Input, Output] (0 => SPIHD) (0 => SPIHD)) + (13, [Input, Output] (0 => SPIWP) (0 => SPIWP)) + (14, [Input, Output] () (0 => SPICS0)) + (15, [Input, Output] () (0 => SPICLK_MUX)) + (16, [Input, Output] (0 => SPID) (0 => SPID)) + (17, [Input, Output] (0 => SPIQ) (0 => SPIQ)) + (18, [Input, Output]) + (19, [Input, Output]) + (20, [Input, Output] (0 => U0RXD) ()) + (21, [Input, Output] () (0 => U0TXD)) + ] } diff --git a/esp-hal/src/soc/esp32c6/efuse/mod.rs b/esp-hal/src/soc/esp32c6/efuse/mod.rs index f5cd1105126..9e2906e2af7 100644 --- a/esp-hal/src/soc/esp32c6/efuse/mod.rs +++ b/esp-hal/src/soc/esp32c6/efuse/mod.rs @@ -25,7 +25,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.pins.gpio4, peripherals.pins.gpio5).unwrap(); +//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.GPIO4, peripherals.GPIO5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32c6/gpio.rs b/esp-hal/src/soc/esp32c6/gpio.rs index 32c73525600..b7d84a403aa 100644 --- a/esp-hal/src/soc/esp32c6/gpio.rs +++ b/esp-hal/src/soc/esp32c6/gpio.rs @@ -287,40 +287,6 @@ pub enum OutputSignal { GPIO = 128, } -crate::gpio! { - (0, [Input, Output, Analog, RtcIo]) - (1, [Input, Output, Analog, RtcIo]) - (2, [Input, Output, Analog, RtcIo] (2 => FSPIQ) (2 => FSPIQ)) - (3, [Input, Output, Analog, RtcIo]) - (4, [Input, Output, Analog, RtcIo] (2 => FSPIHD) (0 => USB_JTAG_TMS 2 => FSPIHD)) - (5, [Input, Output, Analog, RtcIo] (2 => FSPIWP) (0 => USB_JTAG_TDI 2 => FSPIWP)) - (6, [Input, Output, Analog, RtcIo] (2 => FSPICLK) (0 => USB_JTAG_TCK 2 => FSPICLK_MUX)) - (7, [Input, Output, Analog, RtcIo] (2 => FSPID) (0 => USB_JTAG_TDO 2 => FSPID)) - (8, [Input, Output]) - (9, [Input, Output]) - (10, [Input, Output]) - (11, [Input, Output]) - (12, [Input, Output]) - (13, [Input, Output]) - (14, [Input, Output]) - (15, [Input, Output]) - (16, [Input, Output] (0 => U0RXD) (2 => FSPICS0)) - (17, [Input, Output] () (0 => U0TXD 2 => FSPICS1)) - (18, [Input, Output] () (2 => FSPICS2)) // 0 => SDIO_CMD but there are no signals since it's a fixed pin - (19, [Input, Output] () (2 => FSPICS3)) // 0 => SDIO_CLK but there are no signals since it's a fixed pin - (20, [Input, Output] () (2 => FSPICS4)) // 0 => SDIO_DATA0 but there are no signals since it's a fixed pin - (21, [Input, Output] () (2 => FSPICS5)) // 0 => SDIO_DATA1 but there are no signals since it's a fixed pin - (22, [Input, Output] () ()) // 0 => SDIO_DATA2 but there are no signals since it's a fixed pin - (23, [Input, Output] () ()) // 0 => SDIO_DATA3 but there are no signals since it's a fixed pin - (24, [Input, Output] () (0 => SPICS0)) - (25, [Input, Output] (0 => SPIQ) (0 => SPIQ)) - (26, [Input, Output] (0 => SPIWP) (0 => SPIWP)) - (27, [Input, Output]) - (28, [Input, Output] (0 => SPIHD) (0 => SPIHD)) - (29, [Input, Output] () (0 => SPICLK_MUX)) - (30, [Input, Output] (0 => SPID) (0 => SPID)) -} - crate::lp_gpio! { 0 1 diff --git a/esp-hal/src/soc/esp32c6/peripherals.rs b/esp-hal/src/soc/esp32c6/peripherals.rs index c983c46b6fc..b521161faf9 100644 --- a/esp-hal/src/soc/esp32c6/peripherals.rs +++ b/esp-hal/src/soc/esp32c6/peripherals.rs @@ -20,80 +20,115 @@ pub(crate) use self::peripherals::*; // peripheral (no `PSRAM`, `RADIO`, etc. peripheral in the PACs), so we're // creating "virtual peripherals" for them. crate::peripherals! { - ADC1 <= virtual, - AES <= AES, - ASSIST_DEBUG <= ASSIST_DEBUG, - ATOMIC <= ATOMIC, - BT <= virtual, - DMA <= DMA (DMA_IN_CH0,DMA_IN_CH1,DMA_IN_CH2,DMA_OUT_CH0,DMA_OUT_CH1,DMA_OUT_CH2), - DS <= DS, - ECC <= ECC, - EFUSE <= EFUSE, - EXTMEM <= EXTMEM, - GPIO_SD <= GPIO_SD, - HINF <= HINF, - HMAC <= HMAC, - HP_APM <= HP_APM, - HP_SYS <= HP_SYS, - I2C0 <= I2C0, - I2S0 <= I2S0 (I2S0), - IEEE802154 <= IEEE802154, - INTERRUPT_CORE0 <= INTERRUPT_CORE0, - INTPRI <= INTPRI, - IO_MUX <= IO_MUX, - LEDC <= LEDC, - LPWR <= LP_CLKRST, - LP_CORE <= virtual, - LP_PERI <= LP_PERI, - LP_ANA <= LP_ANA, - LP_AON <= LP_AON, - LP_APM <= LP_APM, - LP_APM0 <= LP_APM0, - LP_I2C0 <= LP_I2C0, - LP_I2C_ANA_MST <= LP_I2C_ANA_MST, - LP_IO <= LP_IO, - LP_TEE <= LP_TEE, - LP_TIMER <= LP_TIMER, - LP_UART <= LP_UART, - LP_WDT <= LP_WDT, - MCPWM0 <= MCPWM0, - MEM_MONITOR <= MEM_MONITOR, - OTP_DEBUG <= OTP_DEBUG, - PARL_IO <= PARL_IO (PARL_IO), - PAU <= PAU, - PCNT <= PCNT, - PMU <= PMU, - RADIO_CLK <= virtual, - RMT <= RMT, - RNG <= RNG, - RSA <= RSA, - SHA <= SHA, - SLCHOST <= SLCHOST, - SOC_ETM <= SOC_ETM, - SPI0 <= SPI0, - SPI1 <= SPI1, - SPI2 <= SPI2 (SPI2), - SYSTEM <= PCR, - SYSTIMER <= SYSTIMER, - SW_INTERRUPT <= virtual, - TEE <= TEE, - TIMG0 <= TIMG0, - TIMG1 <= TIMG1, - TRACE0 <= TRACE, - TWAI0 <= TWAI0, - TWAI1 <= TWAI1, - UART0 <= UART0, - UART1 <= UART1, - UHCI0 <= UHCI0, - USB_DEVICE <= USB_DEVICE, - WIFI <= virtual, - MEM2MEM1 <= virtual, - MEM2MEM4 <= virtual, - MEM2MEM5 <= virtual, - MEM2MEM10 <= virtual, - MEM2MEM11 <= virtual, - MEM2MEM12 <= virtual, - MEM2MEM13 <= virtual, - MEM2MEM14 <= virtual, - MEM2MEM15 <= virtual, + peripherals: [ + ADC1 <= virtual, + AES <= AES, + ASSIST_DEBUG <= ASSIST_DEBUG, + ATOMIC <= ATOMIC, + BT <= virtual, + DMA <= DMA (DMA_IN_CH0,DMA_IN_CH1,DMA_IN_CH2,DMA_OUT_CH0,DMA_OUT_CH1,DMA_OUT_CH2), + DS <= DS, + ECC <= ECC, + EFUSE <= EFUSE, + EXTMEM <= EXTMEM, + GPIO_SD <= GPIO_SD, + HINF <= HINF, + HMAC <= HMAC, + HP_APM <= HP_APM, + HP_SYS <= HP_SYS, + I2C0 <= I2C0, + I2S0 <= I2S0 (I2S0), + IEEE802154 <= IEEE802154, + INTERRUPT_CORE0 <= INTERRUPT_CORE0, + INTPRI <= INTPRI, + IO_MUX <= IO_MUX, + LEDC <= LEDC, + LPWR <= LP_CLKRST, + LP_CORE <= virtual, + LP_PERI <= LP_PERI, + LP_ANA <= LP_ANA, + LP_AON <= LP_AON, + LP_APM <= LP_APM, + LP_APM0 <= LP_APM0, + LP_I2C0 <= LP_I2C0, + LP_I2C_ANA_MST <= LP_I2C_ANA_MST, + LP_IO <= LP_IO, + LP_TEE <= LP_TEE, + LP_TIMER <= LP_TIMER, + LP_UART <= LP_UART, + LP_WDT <= LP_WDT, + MCPWM0 <= MCPWM0, + MEM_MONITOR <= MEM_MONITOR, + OTP_DEBUG <= OTP_DEBUG, + PARL_IO <= PARL_IO (PARL_IO), + PAU <= PAU, + PCNT <= PCNT, + PMU <= PMU, + RADIO_CLK <= virtual, + RMT <= RMT, + RNG <= RNG, + RSA <= RSA, + SHA <= SHA, + SLCHOST <= SLCHOST, + SOC_ETM <= SOC_ETM, + SPI0 <= SPI0, + SPI1 <= SPI1, + SPI2 <= SPI2 (SPI2), + SYSTEM <= PCR, + SYSTIMER <= SYSTIMER, + SW_INTERRUPT <= virtual, + TEE <= TEE, + TIMG0 <= TIMG0, + TIMG1 <= TIMG1, + TRACE0 <= TRACE, + TWAI0 <= TWAI0, + TWAI1 <= TWAI1, + UART0 <= UART0, + UART1 <= UART1, + UHCI0 <= UHCI0, + USB_DEVICE <= USB_DEVICE, + WIFI <= virtual, + MEM2MEM1 <= virtual, + MEM2MEM4 <= virtual, + MEM2MEM5 <= virtual, + MEM2MEM10 <= virtual, + MEM2MEM11 <= virtual, + MEM2MEM12 <= virtual, + MEM2MEM13 <= virtual, + MEM2MEM14 <= virtual, + MEM2MEM15 <= virtual, + ], + pins: [ + (0, [Input, Output, Analog, RtcIo]) + (1, [Input, Output, Analog, RtcIo]) + (2, [Input, Output, Analog, RtcIo] (2 => FSPIQ) (2 => FSPIQ)) + (3, [Input, Output, Analog, RtcIo]) + (4, [Input, Output, Analog, RtcIo] (2 => FSPIHD) (0 => USB_JTAG_TMS 2 => FSPIHD)) + (5, [Input, Output, Analog, RtcIo] (2 => FSPIWP) (0 => USB_JTAG_TDI 2 => FSPIWP)) + (6, [Input, Output, Analog, RtcIo] (2 => FSPICLK) (0 => USB_JTAG_TCK 2 => FSPICLK_MUX)) + (7, [Input, Output, Analog, RtcIo] (2 => FSPID) (0 => USB_JTAG_TDO 2 => FSPID)) + (8, [Input, Output]) + (9, [Input, Output]) + (10, [Input, Output]) + (11, [Input, Output]) + (12, [Input, Output]) + (13, [Input, Output]) + (14, [Input, Output]) + (15, [Input, Output]) + (16, [Input, Output] (0 => U0RXD) (2 => FSPICS0)) + (17, [Input, Output] () (0 => U0TXD 2 => FSPICS1)) + (18, [Input, Output] () (2 => FSPICS2)) // 0 => SDIO_CMD but there are no signals since it's a fixed pin + (19, [Input, Output] () (2 => FSPICS3)) // 0 => SDIO_CLK but there are no signals since it's a fixed pin + (20, [Input, Output] () (2 => FSPICS4)) // 0 => SDIO_DATA0 but there are no signals since it's a fixed pin + (21, [Input, Output] () (2 => FSPICS5)) // 0 => SDIO_DATA1 but there are no signals since it's a fixed pin + (22, [Input, Output] () ()) // 0 => SDIO_DATA2 but there are no signals since it's a fixed pin + (23, [Input, Output] () ()) // 0 => SDIO_DATA3 but there are no signals since it's a fixed pin + (24, [Input, Output] () (0 => SPICS0)) + (25, [Input, Output] (0 => SPIQ) (0 => SPIQ)) + (26, [Input, Output] (0 => SPIWP) (0 => SPIWP)) + (27, [Input, Output]) + (28, [Input, Output] (0 => SPIHD) (0 => SPIHD)) + (29, [Input, Output] () (0 => SPICLK_MUX)) + (30, [Input, Output] (0 => SPID) (0 => SPID)) + ] } diff --git a/esp-hal/src/soc/esp32h2/efuse/mod.rs b/esp-hal/src/soc/esp32h2/efuse/mod.rs index 40ca4cee29d..eaf75d21d5c 100644 --- a/esp-hal/src/soc/esp32h2/efuse/mod.rs +++ b/esp-hal/src/soc/esp32h2/efuse/mod.rs @@ -25,7 +25,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.pins.gpio4, peripherals.pins.gpio5).unwrap(); +//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.GPIO4, peripherals.GPIO5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32h2/gpio.rs b/esp-hal/src/soc/esp32h2/gpio.rs index fba6b839dd2..ffff2e84797 100644 --- a/esp-hal/src/soc/esp32h2/gpio.rs +++ b/esp-hal/src/soc/esp32h2/gpio.rs @@ -36,10 +36,7 @@ //! registers for both the `PRO CPU` and `APP CPU`. The implementation uses the //! `gpio` peripheral to access the appropriate registers. -use crate::{ - gpio::{AlternateFunction, GpioPin}, - peripherals::GPIO, -}; +use crate::{gpio::AlternateFunction, peripherals::GPIO}; // https://github.com/espressif/esp-idf/blob/df9310a/components/soc/esp32h2/gpio_periph.c#L42 /// The total number of GPIO pins available. @@ -252,37 +249,6 @@ pub enum OutputSignal { GPIO = 128, } -crate::gpio! { - (0, [Input, Output, Analog] (2 => FSPIQ) (2 => FSPIQ)) - (1, [Input, Output, Analog] (2 => FSPICS0) (2 => FSPICS0)) - (2, [Input, Output, Analog] (2 => FSPIWP) (2 => FSPIWP)) - (3, [Input, Output, Analog] (2 => FSPIHD) (2 => FSPIHD)) - (4, [Input, Output, Analog] (2 => FSPICLK) (2 => FSPICLK_MUX)) - (5, [Input, Output, Analog] (2 => FSPID) (2 => FSPID)) - (6, [Input, Output]) - (7, [Input, Output]) - (8, [Input, Output]) - (9, [Input, Output]) - (10, [Input, Output]) - (11, [Input, Output]) - (12, [Input, Output]) - (13, [Input, Output]) - (14, [Input, Output]) - (15, [Input, Output] () (0 => SPICS0)) - (16, [Input, Output] (0 => SPIQ) (0 => SPIQ)) - (17, [Input, Output] (0 => SPIWP) (0 => SPIWP)) - (18, [Input, Output] (0 => SPIHD) (0 => SPIHD)) - (19, [Input, Output] () (0 => SPICLK)) - (20, [Input, Output] (0 => SPID) (0 => SPID)) - (21, [Input, Output]) - (22, [Input, Output]) - (23, [Input, Output] () (2 => FSPICS1)) - (24, [Input, Output] () (2 => FSPICS2)) - (25, [Input, Output] () (2 => FSPICS3)) - (26, [Input, Output] () (2 => FSPICS4)) - (27, [Input, Output] () (2 => FSPICS5)) -} - #[derive(Clone, Copy)] pub(crate) enum InterruptStatusRegisterAccess { Bank0, diff --git a/esp-hal/src/soc/esp32h2/peripherals.rs b/esp-hal/src/soc/esp32h2/peripherals.rs index 9a2606c9700..9f2c0cdb7df 100644 --- a/esp-hal/src/soc/esp32h2/peripherals.rs +++ b/esp-hal/src/soc/esp32h2/peripherals.rs @@ -20,70 +20,102 @@ pub(crate) use self::peripherals::*; // peripheral (no `PSRAM`, `RADIO`, etc. peripheral in the PACs), so we're // creating "virtual peripherals" for them. crate::peripherals! { - ADC1 <= virtual, - AES <= AES, - ASSIST_DEBUG <= ASSIST_DEBUG, - BT <= virtual, - DMA <= DMA (DMA_IN_CH0,DMA_IN_CH1,DMA_IN_CH2,DMA_OUT_CH0,DMA_OUT_CH1,DMA_OUT_CH2), - DS <= DS, - ECC <= ECC, - EFUSE <= EFUSE, - GPIO_SD <= GPIO_SD, - HMAC <= HMAC, - HP_APM <= HP_APM, - HP_SYS <= HP_SYS, - I2C0 <= I2C0, - I2C1 <= I2C1, - I2S0 <= I2S0 (I2S0), - IEEE802154 <= IEEE802154, - INTERRUPT_CORE0 <= INTERRUPT_CORE0, - INTPRI <= INTPRI, - IO_MUX <= IO_MUX, - LEDC <= LEDC, - LPWR <= LP_CLKRST, - LP_ANA <= LP_ANA, - LP_AON <= LP_AON, - LP_APM <= LP_APM, - LP_PERI <= LP_PERI, - LP_TIMER <= LP_TIMER, - LP_WDT <= LP_WDT, - MCPWM0 <= MCPWM0, - MEM_MONITOR <= MEM_MONITOR, - MODEM_LPCON <= MODEM_LPCON, - MODEM_SYSCON <= MODEM_SYSCON, - OTP_DEBUG <= OTP_DEBUG, - PARL_IO <= PARL_IO (PARL_IO_TX, PARL_IO_RX), - PAU <= PAU, - PCNT <= PCNT, - PMU <= PMU, - RADIO_CLK <= virtual, - RMT <= RMT, - RNG <= RNG, - RSA <= RSA, - SHA <= SHA, - SOC_ETM <= SOC_ETM, - SPI0 <= SPI0, - SPI1 <= SPI1, - SPI2 <= SPI2 (SPI2), - SYSTEM <= PCR, - SYSTIMER <= SYSTIMER, - SW_INTERRUPT <= virtual, - TEE <= TEE, - TIMG0 <= TIMG0, - TIMG1 <= TIMG1, - TRACE0 <= TRACE, - TWAI0 <= TWAI0, - UART0 <= UART0, - UART1 <= UART1, - UHCI0 <= UHCI0, - USB_DEVICE <= USB_DEVICE, - MEM2MEM1 <= virtual, - MEM2MEM4 <= virtual, - MEM2MEM5 <= virtual, - MEM2MEM10 <= virtual, - MEM2MEM11 <= virtual, - MEM2MEM12 <= virtual, - MEM2MEM13 <= virtual, - MEM2MEM14 <= virtual, - MEM2MEM15 <= virtual, + peripherals: [ + ADC1 <= virtual, + AES <= AES, + ASSIST_DEBUG <= ASSIST_DEBUG, + BT <= virtual, + DMA <= DMA (DMA_IN_CH0,DMA_IN_CH1,DMA_IN_CH2,DMA_OUT_CH0,DMA_OUT_CH1,DMA_OUT_CH2), + DS <= DS, + ECC <= ECC, + EFUSE <= EFUSE, + GPIO_SD <= GPIO_SD, + HMAC <= HMAC, + HP_APM <= HP_APM, + HP_SYS <= HP_SYS, + I2C0 <= I2C0, + I2C1 <= I2C1, + I2S0 <= I2S0 (I2S0), + IEEE802154 <= IEEE802154, + INTERRUPT_CORE0 <= INTERRUPT_CORE0, + INTPRI <= INTPRI, + IO_MUX <= IO_MUX, + LEDC <= LEDC, + LPWR <= LP_CLKRST, + LP_ANA <= LP_ANA, + LP_AON <= LP_AON, + LP_APM <= LP_APM, + LP_PERI <= LP_PERI, + LP_TIMER <= LP_TIMER, + LP_WDT <= LP_WDT, + MCPWM0 <= MCPWM0, + MEM_MONITOR <= MEM_MONITOR, + MODEM_LPCON <= MODEM_LPCON, + MODEM_SYSCON <= MODEM_SYSCON, + OTP_DEBUG <= OTP_DEBUG, + PARL_IO <= PARL_IO (PARL_IO_TX, PARL_IO_RX), + PAU <= PAU, + PCNT <= PCNT, + PMU <= PMU, + RADIO_CLK <= virtual, + RMT <= RMT, + RNG <= RNG, + RSA <= RSA, + SHA <= SHA, + SOC_ETM <= SOC_ETM, + SPI0 <= SPI0, + SPI1 <= SPI1, + SPI2 <= SPI2 (SPI2), + SYSTEM <= PCR, + SYSTIMER <= SYSTIMER, + SW_INTERRUPT <= virtual, + TEE <= TEE, + TIMG0 <= TIMG0, + TIMG1 <= TIMG1, + TRACE0 <= TRACE, + TWAI0 <= TWAI0, + UART0 <= UART0, + UART1 <= UART1, + UHCI0 <= UHCI0, + USB_DEVICE <= USB_DEVICE, + MEM2MEM1 <= virtual, + MEM2MEM4 <= virtual, + MEM2MEM5 <= virtual, + MEM2MEM10 <= virtual, + MEM2MEM11 <= virtual, + MEM2MEM12 <= virtual, + MEM2MEM13 <= virtual, + MEM2MEM14 <= virtual, + MEM2MEM15 <= virtual, + ], + pins: [ + (0, [Input, Output, Analog] (2 => FSPIQ) (2 => FSPIQ)) + (1, [Input, Output, Analog] (2 => FSPICS0) (2 => FSPICS0)) + (2, [Input, Output, Analog] (2 => FSPIWP) (2 => FSPIWP)) + (3, [Input, Output, Analog] (2 => FSPIHD) (2 => FSPIHD)) + (4, [Input, Output, Analog] (2 => FSPICLK) (2 => FSPICLK_MUX)) + (5, [Input, Output, Analog] (2 => FSPID) (2 => FSPID)) + (6, [Input, Output]) + (7, [Input, Output]) + (8, [Input, Output]) + (9, [Input, Output]) + (10, [Input, Output]) + (11, [Input, Output]) + (12, [Input, Output]) + (13, [Input, Output]) + (14, [Input, Output]) + (15, [Input, Output] () (0 => SPICS0)) + (16, [Input, Output] (0 => SPIQ) (0 => SPIQ)) + (17, [Input, Output] (0 => SPIWP) (0 => SPIWP)) + (18, [Input, Output] (0 => SPIHD) (0 => SPIHD)) + (19, [Input, Output] () (0 => SPICLK)) + (20, [Input, Output] (0 => SPID) (0 => SPID)) + (21, [Input, Output]) + (22, [Input, Output]) + (23, [Input, Output] () (2 => FSPICS1)) + (24, [Input, Output] () (2 => FSPICS2)) + (25, [Input, Output] () (2 => FSPICS3)) + (26, [Input, Output] () (2 => FSPICS4)) + (27, [Input, Output] () (2 => FSPICS5)) + ] } diff --git a/esp-hal/src/soc/esp32s2/efuse/mod.rs b/esp-hal/src/soc/esp32s2/efuse/mod.rs index 523e2d92151..99e168dbdea 100644 --- a/esp-hal/src/soc/esp32s2/efuse/mod.rs +++ b/esp-hal/src/soc/esp32s2/efuse/mod.rs @@ -27,7 +27,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.pins.gpio4, peripherals.pins.gpio5).unwrap(); +//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.GPIO4, peripherals.GPIO5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32s2/gpio.rs b/esp-hal/src/soc/esp32s2/gpio.rs index faa6b8bcd6d..58355676851 100644 --- a/esp-hal/src/soc/esp32s2/gpio.rs +++ b/esp-hal/src/soc/esp32s2/gpio.rs @@ -415,53 +415,6 @@ macro_rules! rtcio_analog { }; } -crate::gpio! { - (0, [Input, Output, Analog, RtcIo]) - (1, [Input, Output, Analog, RtcIo]) - (2, [Input, Output, Analog, RtcIo]) - (3, [Input, Output, Analog, RtcIo]) - (4, [Input, Output, Analog, RtcIo]) - (5, [Input, Output, Analog, RtcIo]) - (6, [Input, Output, Analog, RtcIo]) - (7, [Input, Output, Analog, RtcIo]) - (8, [Input, Output, Analog, RtcIo]) - (9, [Input, Output, Analog, RtcIo]) - (10, [Input, Output, Analog, RtcIo]) - (11, [Input, Output, Analog, RtcIo]) - (12, [Input, Output, Analog, RtcIo]) - (13, [Input, Output, Analog, RtcIo]) - (14, [Input, Output, Analog, RtcIo]) - (15, [Input, Output, Analog, RtcIo]) - (16, [Input, Output, Analog, RtcIo]) - (17, [Input, Output, Analog, RtcIo]) - (18, [Input, Output, Analog, RtcIo]) - (19, [Input, Output, Analog, RtcIo]) - (20, [Input, Output, Analog, RtcIo]) - (21, [Input, Output, Analog, RtcIo]) - - (26, [Input, Output]) - (27, [Input, Output]) - (28, [Input, Output]) - (29, [Input, Output]) - (30, [Input, Output]) - (31, [Input, Output]) - (32, [Input, Output]) - (33, [Input, Output]) - (34, [Input, Output]) - (35, [Input, Output]) - (36, [Input, Output]) - (37, [Input, Output]) - (38, [Input, Output]) - (39, [Input, Output]) - (40, [Input, Output]) - (41, [Input, Output]) - (42, [Input, Output]) - (43, [Input, Output]) - (44, [Input, Output]) - (45, [Input, Output]) - (46, [Input, Output]) -} - rtcio_analog! { ( 0, touch_pad(0), "", touch_pad0_hold ) ( 1, touch_pad(1), "", touch_pad1_hold ) diff --git a/esp-hal/src/soc/esp32s2/peripherals.rs b/esp-hal/src/soc/esp32s2/peripherals.rs index fc3634e17ee..81f67a9e5f0 100644 --- a/esp-hal/src/soc/esp32s2/peripherals.rs +++ b/esp-hal/src/soc/esp32s2/peripherals.rs @@ -20,52 +20,100 @@ pub(crate) use self::peripherals::*; // peripheral (no `PSRAM`, `RADIO`, etc. peripheral in the PACs), so we're // creating "virtual peripherals" for them. crate::peripherals! { - ADC1 <= virtual, - ADC2 <= virtual, - AES <= AES, - DAC1 <= virtual, - DAC2 <= virtual, - DMA <= virtual, - DEDICATED_GPIO <= DEDICATED_GPIO, - DS <= DS, - EFUSE <= EFUSE, - EXTMEM <= EXTMEM, - GPIO_SD <= GPIO_SD, - HMAC <= HMAC, - I2C0 <= I2C0, - I2C1 <= I2C1, - I2S0 <= I2S0 (I2S0), - INTERRUPT_CORE0 <= INTERRUPT_CORE0, - IO_MUX <= IO_MUX, - LEDC <= LEDC, - LPWR <= RTC_CNTL, - PCNT <= PCNT, - PMS <= PMS, - PSRAM <= virtual, - RADIO_CLK <= virtual, - RMT <= RMT, - RNG <= RNG, - RSA <= RSA, - RTC_IO <= RTC_IO, - RTC_I2C <= RTC_I2C, - SHA <= SHA, - SPI0 <= SPI0, - SPI1 <= SPI1, - SPI2 <= SPI2 (SPI2_DMA, SPI2), - SPI3 <= SPI3 (SPI3_DMA, SPI3), - SYSCON <= SYSCON, - SYSTEM <= SYSTEM, - SYSTIMER <= SYSTIMER, - SW_INTERRUPT <= virtual, - TIMG0 <= TIMG0, - TIMG1 <= TIMG1, - TWAI0 <= TWAI0, - UART0 <= UART0, - UART1 <= UART1, - UHCI0 <= UHCI0, - ULP_RISCV_CORE <= virtual, - USB0 <= USB0, - USB_WRAP <= USB_WRAP, - WIFI <= virtual, - XTS_AES <= XTS_AES, + peripherals: [ + ADC1 <= virtual, + ADC2 <= virtual, + AES <= AES, + DAC1 <= virtual, + DAC2 <= virtual, + DMA <= virtual, + DEDICATED_GPIO <= DEDICATED_GPIO, + DS <= DS, + EFUSE <= EFUSE, + EXTMEM <= EXTMEM, + GPIO_SD <= GPIO_SD, + HMAC <= HMAC, + I2C0 <= I2C0, + I2C1 <= I2C1, + I2S0 <= I2S0 (I2S0), + INTERRUPT_CORE0 <= INTERRUPT_CORE0, + IO_MUX <= IO_MUX, + LEDC <= LEDC, + LPWR <= RTC_CNTL, + PCNT <= PCNT, + PMS <= PMS, + PSRAM <= virtual, + RADIO_CLK <= virtual, + RMT <= RMT, + RNG <= RNG, + RSA <= RSA, + RTC_IO <= RTC_IO, + RTC_I2C <= RTC_I2C, + SHA <= SHA, + SPI0 <= SPI0, + SPI1 <= SPI1, + SPI2 <= SPI2 (SPI2_DMA, SPI2), + SPI3 <= SPI3 (SPI3_DMA, SPI3), + SYSCON <= SYSCON, + SYSTEM <= SYSTEM, + SYSTIMER <= SYSTIMER, + SW_INTERRUPT <= virtual, + TIMG0 <= TIMG0, + TIMG1 <= TIMG1, + TWAI0 <= TWAI0, + UART0 <= UART0, + UART1 <= UART1, + UHCI0 <= UHCI0, + ULP_RISCV_CORE <= virtual, + USB0 <= USB0, + USB_WRAP <= USB_WRAP, + WIFI <= virtual, + XTS_AES <= XTS_AES, + ], + pins: [ + (0, [Input, Output, Analog, RtcIo]) + (1, [Input, Output, Analog, RtcIo]) + (2, [Input, Output, Analog, RtcIo]) + (3, [Input, Output, Analog, RtcIo]) + (4, [Input, Output, Analog, RtcIo]) + (5, [Input, Output, Analog, RtcIo]) + (6, [Input, Output, Analog, RtcIo]) + (7, [Input, Output, Analog, RtcIo]) + (8, [Input, Output, Analog, RtcIo]) + (9, [Input, Output, Analog, RtcIo]) + (10, [Input, Output, Analog, RtcIo]) + (11, [Input, Output, Analog, RtcIo]) + (12, [Input, Output, Analog, RtcIo]) + (13, [Input, Output, Analog, RtcIo]) + (14, [Input, Output, Analog, RtcIo]) + (15, [Input, Output, Analog, RtcIo]) + (16, [Input, Output, Analog, RtcIo]) + (17, [Input, Output, Analog, RtcIo]) + (18, [Input, Output, Analog, RtcIo]) + (19, [Input, Output, Analog, RtcIo]) + (20, [Input, Output, Analog, RtcIo]) + (21, [Input, Output, Analog, RtcIo]) + + (26, [Input, Output]) + (27, [Input, Output]) + (28, [Input, Output]) + (29, [Input, Output]) + (30, [Input, Output]) + (31, [Input, Output]) + (32, [Input, Output]) + (33, [Input, Output]) + (34, [Input, Output]) + (35, [Input, Output]) + (36, [Input, Output]) + (37, [Input, Output]) + (38, [Input, Output]) + (39, [Input, Output]) + (40, [Input, Output]) + (41, [Input, Output]) + (42, [Input, Output]) + (43, [Input, Output]) + (44, [Input, Output]) + (45, [Input, Output]) + (46, [Input, Output]) + ] } diff --git a/esp-hal/src/soc/esp32s3/efuse/mod.rs b/esp-hal/src/soc/esp32s3/efuse/mod.rs index 2c1ff3c9d3c..2d2257fe43d 100644 --- a/esp-hal/src/soc/esp32s3/efuse/mod.rs +++ b/esp-hal/src/soc/esp32s3/efuse/mod.rs @@ -25,7 +25,7 @@ //! # use esp_hal::uart::Uart; //! # use core::writeln; //! # use core::fmt::Write; -//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.pins.gpio4, peripherals.pins.gpio5).unwrap(); +//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.GPIO4, peripherals.GPIO5).unwrap(); //! let mac_address = Efuse::read_base_mac_address(); //! writeln!( //! serial_tx, diff --git a/esp-hal/src/soc/esp32s3/gpio.rs b/esp-hal/src/soc/esp32s3/gpio.rs index 2822ec1cfa0..8c71a0ad109 100644 --- a/esp-hal/src/soc/esp32s3/gpio.rs +++ b/esp-hal/src/soc/esp32s3/gpio.rs @@ -447,54 +447,6 @@ macro_rules! rtcio_analog { }; } -crate::gpio! { - (0, [Input, Output, Analog, RtcIo]) - (1, [Input, Output, Analog, RtcIo]) - (2, [Input, Output, Analog, RtcIo]) - (3, [Input, Output, Analog, RtcIo]) - (4, [Input, Output, Analog, RtcIo]) - (5, [Input, Output, Analog, RtcIo]) - (6, [Input, Output, Analog, RtcIo]) - (7, [Input, Output, Analog, RtcIo]) - (8, [Input, Output, Analog, RtcIo] () (3 => SUBSPICS1)) - (9, [Input, Output, Analog, RtcIo] (3 => SUBSPIHD 4 => FSPIHD) (3 => SUBSPIHD 4 => FSPIHD)) - (10, [Input, Output, Analog, RtcIo] (2 => FSPIIO4 4 => FSPICS0) (2 => FSPIIO4 3 => SUBSPICS0 4 => FSPICS0)) - (11, [Input, Output, Analog, RtcIo] (2 => FSPIIO5 3 => SUBSPID 4 => FSPID) (2 => FSPIIO5 3 => SUBSPID 4 => FSPID)) - (12, [Input, Output, Analog, RtcIo] (2 => FSPIIO6 4 => FSPICLK) (2 => FSPIIO6 3=> SUBSPICLK 4 => FSPICLK)) - (13, [Input, Output, Analog, RtcIo] (2 => FSPIIO7 3 => SUBSPIQ 4 => FSPIQ) (2 => FSPIIO7 3 => SUBSPIQ 4 => FSPIQ)) - (14, [Input, Output, Analog, RtcIo] (3 => SUBSPIWP 4 => FSPIWP) (2 => FSPIDQS 3 => SUBSPIWP 4 => FSPIWP)) - (15, [Input, Output, Analog, RtcIo] () (2 => U0RTS)) - (16, [Input, Output, Analog, RtcIo] (2 => U0CTS) ()) - (17, [Input, Output, Analog, RtcIo] () (2 => U1TXD)) - (18, [Input, Output, Analog, RtcIo] (2 => U1RXD) ()) - (19, [Input, Output, Analog, RtcIo] () (2 => U1RTS)) - (20, [Input, Output, Analog, RtcIo] (2 => U1CTS) ()) - (21, [Input, Output, Analog, RtcIo]) - (26, [Input, Output]) - (27, [Input, Output]) - (28, [Input, Output]) - (29, [Input, Output]) - (30, [Input, Output]) - (31, [Input, Output]) - (32, [Input, Output]) - (33, [Input, Output] (2 => FSPIHD 3 => SUBSPIHD) (2 => FSPIHD 3 => SUBSPIHD)) - (34, [Input, Output] (2 => FSPICS0) (2 => FSPICS0 3 => SUBSPICS0)) - (35, [Input, Output] (2 => FSPID 3 => SUBSPID) (2 => FSPID 3 => SUBSPID)) - (36, [Input, Output] (2 => FSPICLK) (2 => FSPICLK 3 => SUBSPICLK)) - (37, [Input, Output] (2 => FSPIQ 3 => SUBSPIQ 4 => SPIDQS) (2 => FSPIQ 3=> SUBSPIQ 4 => SPIDQS)) - (38, [Input, Output] (2 => FSPIWP 3 => SUBSPIWP) (3 => FSPIWP 3 => SUBSPIWP)) - (39, [Input, Output] () (4 => SUBSPICS1)) - (40, [Input, Output]) - (41, [Input, Output]) - (42, [Input, Output]) - (43, [Input, Output]) - (44, [Input, Output]) - (45, [Input, Output]) - (46, [Input, Output]) - (47, [Input, Output]) - (48, [Input, Output]) -} - rtcio_analog! { ( 0, touch_pad(0), "", touch_pad0_hold ) ( 1, touch_pad(1), "", touch_pad1_hold ) diff --git a/esp-hal/src/soc/esp32s3/peripherals.rs b/esp-hal/src/soc/esp32s3/peripherals.rs index ce061ae487e..c6ab886c9bf 100644 --- a/esp-hal/src/soc/esp32s3/peripherals.rs +++ b/esp-hal/src/soc/esp32s3/peripherals.rs @@ -20,62 +20,111 @@ pub(crate) use self::peripherals::*; // peripheral (no `PSRAM`, `RADIO`, etc. peripheral in the PACs), so we're // creating "virtual peripherals" for them. crate::peripherals! { - ADC1 <= virtual, - ADC2 <= virtual, - AES <= AES, - APB_CTRL <= APB_CTRL, - ASSIST_DEBUG <= ASSIST_DEBUG, - BT <= virtual, - CPU_CTRL <= virtual, - DMA <= DMA (DMA_IN_CH0,DMA_IN_CH1,DMA_IN_CH2,DMA_IN_CH3,DMA_IN_CH4,DMA_OUT_CH0,DMA_OUT_CH1,DMA_OUT_CH2,DMA_OUT_CH3,DMA_OUT_CH4), - DS <= DS, - EFUSE <= EFUSE, - EXTMEM <= EXTMEM, - GPIO_SD <= GPIO_SD, - HMAC <= HMAC, - I2C0 <= I2C0, - I2C1 <= I2C1, - I2S0 <= I2S0 (I2S0), - I2S1 <= I2S1 (I2S1), - INTERRUPT_CORE0 <= INTERRUPT_CORE0, - INTERRUPT_CORE1 <= INTERRUPT_CORE1, - IO_MUX <= IO_MUX, - LCD_CAM <= LCD_CAM, - LEDC <= LEDC, - LPWR <= RTC_CNTL, - PCNT <= PCNT, - PERI_BACKUP <= PERI_BACKUP, - PSRAM <= virtual, - MCPWM0 <= MCPWM0, - MCPWM1 <= MCPWM1, - RADIO_CLK <= virtual, - RMT <= RMT, - RNG <= RNG, - RSA <= RSA, - RTC_I2C <= RTC_I2C, - RTC_IO <= RTC_IO, - SENSITIVE <= SENSITIVE, - SHA <= SHA, - SPI0 <= SPI0, - SPI1 <= SPI1, - SPI2 <= SPI2 (SPI2), - SPI3 <= SPI3 (SPI3), - SYSTEM <= SYSTEM, - SYSTIMER <= SYSTIMER, - SW_INTERRUPT <= virtual, - TIMG0 <= TIMG0, - TIMG1 <= TIMG1, - TWAI0 <= TWAI0, - UART0 <= UART0, - UART1 <= UART1, - UART2 <= UART2, - UHCI0 <= UHCI0, - UHCI1 <= UHCI1, - ULP_RISCV_CORE <= virtual, - USB0 <= USB0, - USB_DEVICE <= USB_DEVICE, - USB_WRAP <= USB_WRAP, - WCL <= WCL, - WIFI <= virtual, - XTS_AES <= XTS_AES, + peripherals: [ + ADC1 <= virtual, + ADC2 <= virtual, + AES <= AES, + APB_CTRL <= APB_CTRL, + ASSIST_DEBUG <= ASSIST_DEBUG, + BT <= virtual, + CPU_CTRL <= virtual, + DMA <= DMA (DMA_IN_CH0,DMA_IN_CH1,DMA_IN_CH2,DMA_IN_CH3,DMA_IN_CH4,DMA_OUT_CH0,DMA_OUT_CH1,DMA_OUT_CH2,DMA_OUT_CH3,DMA_OUT_CH4), + DS <= DS, + EFUSE <= EFUSE, + EXTMEM <= EXTMEM, + GPIO_SD <= GPIO_SD, + HMAC <= HMAC, + I2C0 <= I2C0, + I2C1 <= I2C1, + I2S0 <= I2S0 (I2S0), + I2S1 <= I2S1 (I2S1), + INTERRUPT_CORE0 <= INTERRUPT_CORE0, + INTERRUPT_CORE1 <= INTERRUPT_CORE1, + IO_MUX <= IO_MUX, + LCD_CAM <= LCD_CAM, + LEDC <= LEDC, + LPWR <= RTC_CNTL, + PCNT <= PCNT, + PERI_BACKUP <= PERI_BACKUP, + PSRAM <= virtual, + MCPWM0 <= MCPWM0, + MCPWM1 <= MCPWM1, + RADIO_CLK <= virtual, + RMT <= RMT, + RNG <= RNG, + RSA <= RSA, + RTC_I2C <= RTC_I2C, + RTC_IO <= RTC_IO, + SENSITIVE <= SENSITIVE, + SHA <= SHA, + SPI0 <= SPI0, + SPI1 <= SPI1, + SPI2 <= SPI2 (SPI2), + SPI3 <= SPI3 (SPI3), + SYSTEM <= SYSTEM, + SYSTIMER <= SYSTIMER, + SW_INTERRUPT <= virtual, + TIMG0 <= TIMG0, + TIMG1 <= TIMG1, + TWAI0 <= TWAI0, + UART0 <= UART0, + UART1 <= UART1, + UART2 <= UART2, + UHCI0 <= UHCI0, + UHCI1 <= UHCI1, + ULP_RISCV_CORE <= virtual, + USB0 <= USB0, + USB_DEVICE <= USB_DEVICE, + USB_WRAP <= USB_WRAP, + WCL <= WCL, + WIFI <= virtual, + XTS_AES <= XTS_AES, + ], + pins: [ + (0, [Input, Output, Analog, RtcIo]) + (1, [Input, Output, Analog, RtcIo]) + (2, [Input, Output, Analog, RtcIo]) + (3, [Input, Output, Analog, RtcIo]) + (4, [Input, Output, Analog, RtcIo]) + (5, [Input, Output, Analog, RtcIo]) + (6, [Input, Output, Analog, RtcIo]) + (7, [Input, Output, Analog, RtcIo]) + (8, [Input, Output, Analog, RtcIo] () (3 => SUBSPICS1)) + (9, [Input, Output, Analog, RtcIo] (3 => SUBSPIHD 4 => FSPIHD) (3 => SUBSPIHD 4 => FSPIHD)) + (10, [Input, Output, Analog, RtcIo] (2 => FSPIIO4 4 => FSPICS0) (2 => FSPIIO4 3 => SUBSPICS0 4 => FSPICS0)) + (11, [Input, Output, Analog, RtcIo] (2 => FSPIIO5 3 => SUBSPID 4 => FSPID) (2 => FSPIIO5 3 => SUBSPID 4 => FSPID)) + (12, [Input, Output, Analog, RtcIo] (2 => FSPIIO6 4 => FSPICLK) (2 => FSPIIO6 3=> SUBSPICLK 4 => FSPICLK)) + (13, [Input, Output, Analog, RtcIo] (2 => FSPIIO7 3 => SUBSPIQ 4 => FSPIQ) (2 => FSPIIO7 3 => SUBSPIQ 4 => FSPIQ)) + (14, [Input, Output, Analog, RtcIo] (3 => SUBSPIWP 4 => FSPIWP) (2 => FSPIDQS 3 => SUBSPIWP 4 => FSPIWP)) + (15, [Input, Output, Analog, RtcIo] () (2 => U0RTS)) + (16, [Input, Output, Analog, RtcIo] (2 => U0CTS) ()) + (17, [Input, Output, Analog, RtcIo] () (2 => U1TXD)) + (18, [Input, Output, Analog, RtcIo] (2 => U1RXD) ()) + (19, [Input, Output, Analog, RtcIo] () (2 => U1RTS)) + (20, [Input, Output, Analog, RtcIo] (2 => U1CTS) ()) + (21, [Input, Output, Analog, RtcIo]) + (26, [Input, Output]) + (27, [Input, Output]) + (28, [Input, Output]) + (29, [Input, Output]) + (30, [Input, Output]) + (31, [Input, Output]) + (32, [Input, Output]) + (33, [Input, Output] (2 => FSPIHD 3 => SUBSPIHD) (2 => FSPIHD 3 => SUBSPIHD)) + (34, [Input, Output] (2 => FSPICS0) (2 => FSPICS0 3 => SUBSPICS0)) + (35, [Input, Output] (2 => FSPID 3 => SUBSPID) (2 => FSPID 3 => SUBSPID)) + (36, [Input, Output] (2 => FSPICLK) (2 => FSPICLK 3 => SUBSPICLK)) + (37, [Input, Output] (2 => FSPIQ 3 => SUBSPIQ 4 => SPIDQS) (2 => FSPIQ 3=> SUBSPIQ 4 => SPIDQS)) + (38, [Input, Output] (2 => FSPIWP 3 => SUBSPIWP) (3 => FSPIWP 3 => SUBSPIWP)) + (39, [Input, Output] () (4 => SUBSPICS1)) + (40, [Input, Output]) + (41, [Input, Output]) + (42, [Input, Output]) + (43, [Input, Output]) + (44, [Input, Output]) + (45, [Input, Output]) + (46, [Input, Output]) + (47, [Input, Output]) + (48, [Input, Output]) + ] } diff --git a/esp-hal/src/spi/master.rs b/esp-hal/src/spi/master.rs index 3987bb3a749..1430a5269c3 100644 --- a/esp-hal/src/spi/master.rs +++ b/esp-hal/src/spi/master.rs @@ -40,10 +40,10 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::spi::SpiMode; //! # use esp_hal::spi::master::{Config, Spi}; -//! let sclk = peripherals.pins.gpio0; -//! let miso = peripherals.pins.gpio2; -//! let mosi = peripherals.pins.gpio1; -//! let cs = peripherals.pins.gpio5; +//! let sclk = peripherals.GPIO0; +//! let miso = peripherals.GPIO2; +//! let mosi = peripherals.GPIO1; +//! let cs = peripherals.GPIO5; //! //! let mut spi = Spi::new_with_config( //! peripherals.SPI2, diff --git a/esp-hal/src/spi/slave.rs b/esp-hal/src/spi/slave.rs index a443ebf911a..0ffd707d1eb 100644 --- a/esp-hal/src/spi/slave.rs +++ b/esp-hal/src/spi/slave.rs @@ -23,10 +23,10 @@ //! let dma = Dma::new(peripherals.DMA); #![cfg_attr(pdma, doc = "let dma_channel = dma.spi2channel;")] #![cfg_attr(gdma, doc = "let dma_channel = dma.channel0;")] -//! let sclk = peripherals.pins.gpio0; -//! let miso = peripherals.pins.gpio1; -//! let mosi = peripherals.pins.gpio2; -//! let cs = peripherals.pins.gpio3; +//! let sclk = peripherals.GPIO0; +//! let miso = peripherals.GPIO1; +//! let mosi = peripherals.GPIO2; +//! let cs = peripherals.GPIO3; //! //! let (rx_buffer, rx_descriptors, tx_buffer, tx_descriptors) = //! dma_buffers!(32000); diff --git a/esp-hal/src/touch.rs b/esp-hal/src/touch.rs index d56e5d80825..66e8dc1c742 100644 --- a/esp-hal/src/touch.rs +++ b/esp-hal/src/touch.rs @@ -10,7 +10,7 @@ //! ```rust, no_run #![doc = crate::before_snippet!()] //! # use esp_hal::touch::{Touch, TouchPad}; -//! let touch_pin0 = peripherals.pins.gpio2; +//! let touch_pin0 = peripherals.GPIO2; //! let touch = Touch::continuous_mode(peripherals.TOUCH, None); //! let mut touchpad = TouchPad::new(touch_pin0, &touch); //! // ... give the peripheral some time for the measurement diff --git a/esp-hal/src/twai/mod.rs b/esp-hal/src/twai/mod.rs index 3686dceeaa8..cfbb1f7ead0 100644 --- a/esp-hal/src/twai/mod.rs +++ b/esp-hal/src/twai/mod.rs @@ -36,8 +36,8 @@ //! # use nb::block; //! // Use GPIO pins 2 and 3 to connect to the respective pins on the TWAI //! // transceiver. -//! let can_rx_pin = peripherals.pins.gpio3; -//! let can_tx_pin = peripherals.pins.gpio2; +//! let can_rx_pin = peripherals.GPIO3; +//! let can_tx_pin = peripherals.GPIO2; //! //! // The speed of the TWAI bus. //! const TWAI_BAUDRATE: twai::BaudRate = BaudRate::B1000K; @@ -88,8 +88,8 @@ //! # use nb::block; //! // Use GPIO pins 2 and 3 to connect to the respective pins on the TWAI //! // transceiver. -//! let can_rx_pin = peripherals.pins.gpio3; -//! let can_tx_pin = peripherals.pins.gpio2; +//! let can_rx_pin = peripherals.GPIO3; +//! let can_tx_pin = peripherals.GPIO2; //! //! // The speed of the TWAI bus. //! const TWAI_BAUDRATE: twai::BaudRate = BaudRate::B1000K; diff --git a/esp-hal/src/uart.rs b/esp-hal/src/uart.rs index 7ab5783e5f9..b67f6b97427 100644 --- a/esp-hal/src/uart.rs +++ b/esp-hal/src/uart.rs @@ -26,8 +26,8 @@ //! //! let mut uart1 = Uart::new( //! peripherals.UART1, -//! peripherals.pins.gpio1, -//! peripherals.pins.gpio2, +//! peripherals.GPIO1, +//! peripherals.GPIO2, //! ).unwrap(); //! # } //! ``` @@ -56,8 +56,8 @@ //! # let mut uart1 = Uart::new_with_config( //! # peripherals.UART1, //! # Config::default(), -//! # peripherals.pins.gpio1, -//! # peripherals.pins.gpio2, +//! # peripherals.GPIO1, +//! # peripherals.GPIO2, //! # ).unwrap(); //! // Write bytes out over the UART: //! uart1.write_bytes(b"Hello, world!").expect("write error!"); @@ -71,8 +71,8 @@ //! # let mut uart1 = Uart::new_with_config( //! # peripherals.UART1, //! # Config::default(), -//! # peripherals.pins.gpio1, -//! # peripherals.pins.gpio2, +//! # peripherals.GPIO1, +//! # peripherals.GPIO2, //! # ).unwrap(); //! // The UART can be split into separate Transmit and Receive components: //! let (mut rx, mut tx) = uart1.split(); @@ -88,8 +88,8 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::uart::Uart; //! -//! let (rx, _) = peripherals.pins.gpio2.split(); -//! let (_, tx) = peripherals.pins.gpio1.split(); +//! let (rx, _) = peripherals.GPIO2.split(); +//! let (_, tx) = peripherals.GPIO1.split(); //! let mut uart1 = Uart::new( //! peripherals.UART1, //! rx.inverted(), @@ -103,8 +103,8 @@ #![doc = crate::before_snippet!()] //! # use esp_hal::uart::{UartTx, UartRx}; //! -//! let tx = UartTx::new(peripherals.UART0, peripherals.pins.gpio1).unwrap(); -//! let rx = UartRx::new(peripherals.UART1, peripherals.pins.gpio2).unwrap(); +//! let tx = UartTx::new(peripherals.UART0, peripherals.GPIO1).unwrap(); +//! let rx = UartRx::new(peripherals.UART1, peripherals.GPIO2).unwrap(); //! # } //! ``` //! diff --git a/examples/src/bin/adc.rs b/examples/src/bin/adc.rs index 83e6a3e01cc..e4c8eb2b423 100644 --- a/examples/src/bin/adc.rs +++ b/examples/src/bin/adc.rs @@ -30,11 +30,11 @@ fn main() -> ! { cfg_if::cfg_if! { if #[cfg(feature = "esp32")] { - let analog_pin = peripherals.pins.gpio32; + let analog_pin = peripherals.GPIO32; } else if #[cfg(any(feature = "esp32s2", feature = "esp32s3"))] { - let analog_pin = peripherals.pins.gpio3; + let analog_pin = peripherals.GPIO3; } else { - let analog_pin = peripherals.pins.gpio2; + let analog_pin = peripherals.GPIO2; } } diff --git a/examples/src/bin/adc_cal.rs b/examples/src/bin/adc_cal.rs index 2a7a7662963..e7d6ceb859d 100644 --- a/examples/src/bin/adc_cal.rs +++ b/examples/src/bin/adc_cal.rs @@ -26,9 +26,9 @@ fn main() -> ! { cfg_if::cfg_if! { if #[cfg(feature = "esp32s3")] { - let analog_pin = peripherals.pins.gpio3; + let analog_pin = peripherals.GPIO3; } else { - let analog_pin = peripherals.pins.gpio2; + let analog_pin = peripherals.GPIO2; } } diff --git a/examples/src/bin/advanced_serial.rs b/examples/src/bin/advanced_serial.rs index 475cc2646c2..0fe4a647f37 100644 --- a/examples/src/bin/advanced_serial.rs +++ b/examples/src/bin/advanced_serial.rs @@ -23,8 +23,8 @@ fn main() -> ! { let mut serial1 = Uart::new( peripherals.UART1, - peripherals.pins.gpio4, - peripherals.pins.gpio5, + peripherals.GPIO4, + peripherals.GPIO5, ) .unwrap(); diff --git a/examples/src/bin/blinky.rs b/examples/src/bin/blinky.rs index 0f48cb83954..f804dda603f 100644 --- a/examples/src/bin/blinky.rs +++ b/examples/src/bin/blinky.rs @@ -21,7 +21,7 @@ fn main() -> ! { // Set GPIO0 as an output, and set its state high initially. - let mut led = Output::new(peripherals.pins.gpio0, Level::High); + let mut led = Output::new(peripherals.GPIO0, Level::High); let delay = Delay::new(); diff --git a/examples/src/bin/blinky_erased_pins.rs b/examples/src/bin/blinky_erased_pins.rs index c3456bbbeb7..140e728e1aa 100644 --- a/examples/src/bin/blinky_erased_pins.rs +++ b/examples/src/bin/blinky_erased_pins.rs @@ -23,15 +23,15 @@ fn main() -> ! { let peripherals = esp_hal::init(esp_hal::Config::default()); // Set LED GPIOs as an output: - let led1 = Output::new(peripherals.pins.gpio2.degrade(), Level::Low); - let led2 = Output::new(peripherals.pins.gpio4.degrade(), Level::Low); - let led3 = Output::new(peripherals.pins.gpio5.degrade(), Level::Low); + let led1 = Output::new(peripherals.GPIO2.degrade(), Level::Low); + let led2 = Output::new(peripherals.GPIO4.degrade(), Level::Low); + let led3 = Output::new(peripherals.GPIO5.degrade(), Level::Low); // Use boot button as an input: #[cfg(any(feature = "esp32", feature = "esp32s2", feature = "esp32s3"))] - let button = peripherals.pins.gpio0.degrade(); + let button = peripherals.GPIO0.degrade(); #[cfg(not(any(feature = "esp32", feature = "esp32s2", feature = "esp32s3")))] - let button = peripherals.pins.gpio9.degrade(); + let button = peripherals.GPIO9.degrade(); let button = Input::new(button, Pull::Up); diff --git a/examples/src/bin/dac.rs b/examples/src/bin/dac.rs index 903e8f6f30e..4bd42b29860 100644 --- a/examples/src/bin/dac.rs +++ b/examples/src/bin/dac.rs @@ -27,11 +27,11 @@ fn main() -> ! { cfg_if::cfg_if! { if #[cfg(feature = "esp32")] { - let dac1_pin = peripherals.pins.gpio25; - let dac2_pin = peripherals.pins.gpio26; + let dac1_pin = peripherals.GPIO25; + let dac2_pin = peripherals.GPIO26; } else if #[cfg(feature = "esp32s2")] { - let dac1_pin = peripherals.pins.gpio17; - let dac2_pin = peripherals.pins.gpio18; + let dac1_pin = peripherals.GPIO17; + let dac2_pin = peripherals.GPIO18; } } diff --git a/examples/src/bin/embassy_i2c.rs b/examples/src/bin/embassy_i2c.rs index 6e1397fc20b..2b7f467ee53 100644 --- a/examples/src/bin/embassy_i2c.rs +++ b/examples/src/bin/embassy_i2c.rs @@ -38,8 +38,8 @@ async fn main(_spawner: Spawner) { config.frequency = 400.kHz(); config }) - .with_sda(peripherals.pins.gpio4) - .with_scl(peripherals.pins.gpio5) + .with_sda(peripherals.GPIO4) + .with_scl(peripherals.GPIO5) .into_async(); let mut lis3dh = Lis3dh::new_i2c(i2c0, SlaveAddr::Alternate).await.unwrap(); diff --git a/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs b/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs index d3c9ddfc5ba..1f7ff1525af 100644 --- a/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs +++ b/examples/src/bin/embassy_i2c_bmp180_calibration_data.rs @@ -38,8 +38,8 @@ async fn main(_spawner: Spawner) { config.frequency = 400.kHz(); config }) - .with_sda(peripherals.pins.gpio4) - .with_scl(peripherals.pins.gpio5) + .with_sda(peripherals.GPIO4) + .with_scl(peripherals.GPIO5) .into_async(); loop { diff --git a/examples/src/bin/embassy_i2s_parallel.rs b/examples/src/bin/embassy_i2s_parallel.rs index f88b69c1d8b..927b95ded17 100644 --- a/examples/src/bin/embassy_i2s_parallel.rs +++ b/examples/src/bin/embassy_i2s_parallel.rs @@ -42,17 +42,17 @@ async fn main(_spawner: Spawner) { let dma_channel = dma.i2s1channel; let i2s = peripherals.I2S1; - let clock = peripherals.pins.gpio25; + let clock = peripherals.GPIO25; let pins = TxEightBits::new( - peripherals.pins.gpio16, - peripherals.pins.gpio4, - peripherals.pins.gpio17, - peripherals.pins.gpio18, - peripherals.pins.gpio5, - peripherals.pins.gpio19, - peripherals.pins.gpio12, - peripherals.pins.gpio14, + peripherals.GPIO16, + peripherals.GPIO4, + peripherals.GPIO17, + peripherals.GPIO18, + peripherals.GPIO5, + peripherals.GPIO19, + peripherals.GPIO12, + peripherals.GPIO14, ); let (_, _, tx_buffer, tx_descriptors) = dma_buffers!(0, BUFFER_SIZE); diff --git a/examples/src/bin/embassy_i2s_read.rs b/examples/src/bin/embassy_i2s_read.rs index ae6a8e79233..612ee4ad9f5 100644 --- a/examples/src/bin/embassy_i2s_read.rs +++ b/examples/src/bin/embassy_i2s_read.rs @@ -56,13 +56,13 @@ async fn main(_spawner: Spawner) { .into_async(); #[cfg(not(feature = "esp32"))] - let i2s = i2s.with_mclk(peripherals.pins.gpio0); + let i2s = i2s.with_mclk(peripherals.GPIO0); let i2s_rx = i2s .i2s_rx - .with_bclk(peripherals.pins.gpio2) - .with_ws(peripherals.pins.gpio4) - .with_din(peripherals.pins.gpio5) + .with_bclk(peripherals.GPIO2) + .with_ws(peripherals.GPIO4) + .with_din(peripherals.GPIO5) .build(); let buffer = rx_buffer; diff --git a/examples/src/bin/embassy_i2s_sound.rs b/examples/src/bin/embassy_i2s_sound.rs index 4298c8b1ea9..fd06eff7a00 100644 --- a/examples/src/bin/embassy_i2s_sound.rs +++ b/examples/src/bin/embassy_i2s_sound.rs @@ -79,9 +79,9 @@ async fn main(_spawner: Spawner) { let i2s_tx = i2s .i2s_tx - .with_bclk(peripherals.pins.gpio2) - .with_ws(peripherals.pins.gpio4) - .with_dout(peripherals.pins.gpio5) + .with_bclk(peripherals.GPIO2) + .with_ws(peripherals.GPIO4) + .with_dout(peripherals.GPIO5) .build(); let data = diff --git a/examples/src/bin/embassy_multicore.rs b/examples/src/bin/embassy_multicore.rs index 0dddeed44ca..6def339d64d 100644 --- a/examples/src/bin/embassy_multicore.rs +++ b/examples/src/bin/embassy_multicore.rs @@ -63,7 +63,7 @@ async fn main(_spawner: Spawner) { static LED_CTRL: StaticCell> = StaticCell::new(); let led_ctrl_signal = &*LED_CTRL.init(Signal::new()); - let led = Output::new(peripherals.pins.gpio0, Level::Low); + let led = Output::new(peripherals.GPIO0, Level::Low); let _guard = cpu_control .start_app_core(unsafe { &mut *addr_of_mut!(APP_CORE_STACK) }, move || { diff --git a/examples/src/bin/embassy_multicore_interrupt.rs b/examples/src/bin/embassy_multicore_interrupt.rs index f87fb08fd7b..7a1de606c95 100644 --- a/examples/src/bin/embassy_multicore_interrupt.rs +++ b/examples/src/bin/embassy_multicore_interrupt.rs @@ -85,7 +85,7 @@ fn main() -> ! { static LED_CTRL: StaticCell> = StaticCell::new(); let led_ctrl_signal = &*LED_CTRL.init(Signal::new()); - let led = Output::new(peripherals.pins.gpio0, Level::Low); + let led = Output::new(peripherals.GPIO0, Level::Low); static EXECUTOR_CORE_1: StaticCell> = StaticCell::new(); let executor_core1 = InterruptExecutor::new(sw_ints.software_interrupt1); diff --git a/examples/src/bin/embassy_parl_io_rx.rs b/examples/src/bin/embassy_parl_io_rx.rs index aa896ad2d49..9b589992dc0 100644 --- a/examples/src/bin/embassy_parl_io_rx.rs +++ b/examples/src/bin/embassy_parl_io_rx.rs @@ -36,10 +36,10 @@ async fn main(_spawner: Spawner) { let dma_channel = dma.channel0; let mut rx_pins = RxFourBits::new( - peripherals.pins.gpio1, - peripherals.pins.gpio2, - peripherals.pins.gpio3, - peripherals.pins.gpio4, + peripherals.GPIO1, + peripherals.GPIO2, + peripherals.GPIO3, + peripherals.GPIO4, ); let parl_io = ParlIoRxOnly::new( diff --git a/examples/src/bin/embassy_parl_io_tx.rs b/examples/src/bin/embassy_parl_io_tx.rs index d538af55ec0..44302552bde 100644 --- a/examples/src/bin/embassy_parl_io_tx.rs +++ b/examples/src/bin/embassy_parl_io_tx.rs @@ -47,13 +47,13 @@ async fn main(_spawner: Spawner) { let dma_channel = dma.channel0; let tx_pins = TxFourBits::new( - peripherals.pins.gpio1, - peripherals.pins.gpio2, - peripherals.pins.gpio3, - peripherals.pins.gpio4, + peripherals.GPIO1, + peripherals.GPIO2, + peripherals.GPIO3, + peripherals.GPIO4, ); - let mut pin_conf = TxPinConfigWithValidPin::new(tx_pins, peripherals.pins.gpio5); + let mut pin_conf = TxPinConfigWithValidPin::new(tx_pins, peripherals.GPIO5); let parl_io = ParlIoTxOnly::new( peripherals.PARL_IO, @@ -65,7 +65,7 @@ async fn main(_spawner: Spawner) { ) .unwrap(); - let mut clock_pin = ClkOutPin::new(peripherals.pins.gpio8); + let mut clock_pin = ClkOutPin::new(peripherals.GPIO8); let mut parl_io_tx = parl_io .tx diff --git a/examples/src/bin/embassy_rmt_rx.rs b/examples/src/bin/embassy_rmt_rx.rs index d42f73d047a..08c5f8bc28d 100644 --- a/examples/src/bin/embassy_rmt_rx.rs +++ b/examples/src/bin/embassy_rmt_rx.rs @@ -61,16 +61,16 @@ async fn main(spawner: Spawner) { cfg_if::cfg_if! { if #[cfg(any(feature = "esp32", feature = "esp32s2"))] { - let mut channel = rmt.channel0.configure(peripherals.pins.gpio4, rx_config).unwrap(); + let mut channel = rmt.channel0.configure(peripherals.GPIO4, rx_config).unwrap(); } else if #[cfg(feature = "esp32s3")] { - let mut channel = rmt.channel7.configure(peripherals.pins.gpio4, rx_config).unwrap(); + let mut channel = rmt.channel7.configure(peripherals.GPIO4, rx_config).unwrap(); } else { - let mut channel = rmt.channel2.configure(peripherals.pins.gpio4, rx_config).unwrap(); + let mut channel = rmt.channel2.configure(peripherals.GPIO4, rx_config).unwrap(); } } spawner - .spawn(signal_task(Output::new(peripherals.pins.gpio5, Level::Low))) + .spawn(signal_task(Output::new(peripherals.GPIO5, Level::Low))) .unwrap(); let mut data = [PulseCode { diff --git a/examples/src/bin/embassy_rmt_tx.rs b/examples/src/bin/embassy_rmt_tx.rs index 9d1000494ab..5943c453700 100644 --- a/examples/src/bin/embassy_rmt_tx.rs +++ b/examples/src/bin/embassy_rmt_tx.rs @@ -42,7 +42,7 @@ async fn main(_spawner: Spawner) { let mut channel = rmt .channel0 .configure( - peripherals.pins.gpio4, + peripherals.GPIO4, TxChannelConfig { clk_divider: 255, ..TxChannelConfig::default() diff --git a/examples/src/bin/embassy_serial.rs b/examples/src/bin/embassy_serial.rs index a89ddef1372..643bac9285c 100644 --- a/examples/src/bin/embassy_serial.rs +++ b/examples/src/bin/embassy_serial.rs @@ -73,17 +73,17 @@ async fn main(spawner: Spawner) { // Default pins for Uart/Serial communication cfg_if::cfg_if! { if #[cfg(feature = "esp32")] { - let (tx_pin, rx_pin) = (peripherals.pins.gpio1, peripherals.pins.gpio3); + let (tx_pin, rx_pin) = (peripherals.GPIO1, peripherals.GPIO3); } else if #[cfg(feature = "esp32c2")] { - let (tx_pin, rx_pin) = (peripherals.pins.gpio20, peripherals.pins.gpio19); + let (tx_pin, rx_pin) = (peripherals.GPIO20, peripherals.GPIO19); } else if #[cfg(feature = "esp32c3")] { - let (tx_pin, rx_pin) = (peripherals.pins.gpio21, peripherals.pins.gpio20); + let (tx_pin, rx_pin) = (peripherals.GPIO21, peripherals.GPIO20); } else if #[cfg(feature = "esp32c6")] { - let (tx_pin, rx_pin) = (peripherals.pins.gpio16, peripherals.pins.gpio17); + let (tx_pin, rx_pin) = (peripherals.GPIO16, peripherals.GPIO17); } else if #[cfg(feature = "esp32h2")] { - let (tx_pin, rx_pin) = (peripherals.pins.gpio24, peripherals.pins.gpio23); + let (tx_pin, rx_pin) = (peripherals.GPIO24, peripherals.GPIO23); } else if #[cfg(any(feature = "esp32s2", feature = "esp32s3"))] { - let (tx_pin, rx_pin) = (peripherals.pins.gpio43, peripherals.pins.gpio44); + let (tx_pin, rx_pin) = (peripherals.GPIO43, peripherals.GPIO44); } } diff --git a/examples/src/bin/embassy_spi.rs b/examples/src/bin/embassy_spi.rs index fd2a7e6de7e..82a7813f884 100644 --- a/examples/src/bin/embassy_spi.rs +++ b/examples/src/bin/embassy_spi.rs @@ -40,10 +40,10 @@ async fn main(_spawner: Spawner) { let timg0 = TimerGroup::new(peripherals.TIMG0); esp_hal_embassy::init(timg0.timer0); - let sclk = peripherals.pins.gpio0; - let miso = peripherals.pins.gpio2; - let mosi = peripherals.pins.gpio4; - let cs = peripherals.pins.gpio5; + let sclk = peripherals.GPIO0; + let miso = peripherals.GPIO2; + let mosi = peripherals.GPIO4; + let cs = peripherals.GPIO5; let dma = Dma::new(peripherals.DMA); diff --git a/examples/src/bin/embassy_touch.rs b/examples/src/bin/embassy_touch.rs index 643f6684e00..2849d178343 100644 --- a/examples/src/bin/embassy_touch.rs +++ b/examples/src/bin/embassy_touch.rs @@ -33,8 +33,8 @@ async fn main(_spawner: Spawner) { let mut rtc = Rtc::new(peripherals.LPWR); - let touch_pin0 = peripherals.pins.gpio2; - let touch_pin1 = peripherals.pins.gpio4; + let touch_pin0 = peripherals.GPIO2; + let touch_pin1 = peripherals.GPIO4; let touch_cfg = Some(TouchConfig { measurement_duration: Some(0x2000), diff --git a/examples/src/bin/embassy_twai.rs b/examples/src/bin/embassy_twai.rs index ad672cc2d48..d788c75301f 100644 --- a/examples/src/bin/embassy_twai.rs +++ b/examples/src/bin/embassy_twai.rs @@ -92,10 +92,10 @@ async fn main(spawner: Spawner) { esp_hal_embassy::init(timg0.timer0); // Without an external transceiver, we only need a single line between the two MCUs. - let (rx_pin, tx_pin) = peripherals.pins.gpio2.split(); + let (rx_pin, tx_pin) = peripherals.GPIO2.split(); // Use these if you want to use an external transceiver: - // let tx_pin = peripherals.pins.gpio2; - // let rx_pin = peripherals.pins.gpio0; + // let tx_pin = peripherals.GPIO2; + // let rx_pin = peripherals.GPIO0; // The speed of the bus. const TWAI_BAUDRATE: twai::BaudRate = twai::BaudRate::B125K; diff --git a/examples/src/bin/embassy_usb_serial.rs b/examples/src/bin/embassy_usb_serial.rs index 65601da8b9c..29adbdcdb8c 100644 --- a/examples/src/bin/embassy_usb_serial.rs +++ b/examples/src/bin/embassy_usb_serial.rs @@ -38,8 +38,8 @@ async fn main(_spawner: Spawner) { let usb = Usb::new( peripherals.USB0, - peripherals.pins.gpio20, - peripherals.pins.gpio19, + peripherals.GPIO20, + peripherals.GPIO19, ); // Create the driver, from the HAL. diff --git a/examples/src/bin/embassy_wait.rs b/examples/src/bin/embassy_wait.rs index fa9a67dccde..b78a85ff3c4 100644 --- a/examples/src/bin/embassy_wait.rs +++ b/examples/src/bin/embassy_wait.rs @@ -26,9 +26,9 @@ async fn main(_spawner: Spawner) { cfg_if::cfg_if! { if #[cfg(any(feature = "esp32", feature = "esp32s2", feature = "esp32s3"))] { - let mut input = Input::new(peripherals.pins.gpio0, Pull::Down); + let mut input = Input::new(peripherals.GPIO0, Pull::Down); } else { - let mut input = Input::new(peripherals.pins.gpio9, Pull::Down); + let mut input = Input::new(peripherals.GPIO9, Pull::Down); } } diff --git a/examples/src/bin/etm_blinky_systimer.rs b/examples/src/bin/etm_blinky_systimer.rs index 35a30566522..1cdb361e2ef 100644 --- a/examples/src/bin/etm_blinky_systimer.rs +++ b/examples/src/bin/etm_blinky_systimer.rs @@ -30,7 +30,7 @@ fn main() -> ! { let mut alarm0 = syst_alarms.alarm0; alarm0.set_period(1u32.secs()); - let mut led = peripherals.pins.gpio1; + let mut led = peripherals.GPIO1; // setup ETM let gpio_ext = Channels::new(peripherals.GPIO_SD); diff --git a/examples/src/bin/etm_gpio.rs b/examples/src/bin/etm_gpio.rs index cf5d5a9d2e0..d28b1bc3683 100644 --- a/examples/src/bin/etm_gpio.rs +++ b/examples/src/bin/etm_gpio.rs @@ -24,8 +24,8 @@ use esp_hal::{ fn main() -> ! { let peripherals = esp_hal::init(esp_hal::Config::default()); - let mut led = Output::new(peripherals.pins.gpio1, Level::Low); - let button = peripherals.pins.gpio9; + let mut led = Output::new(peripherals.GPIO1, Level::Low); + let button = peripherals.GPIO9; led.set_high(); diff --git a/examples/src/bin/gpio_interrupt.rs b/examples/src/bin/gpio_interrupt.rs index 33a66ae21b1..befe9d6dc84 100644 --- a/examples/src/bin/gpio_interrupt.rs +++ b/examples/src/bin/gpio_interrupt.rs @@ -32,13 +32,13 @@ fn main() -> ! { // Set GPIO2 as an output, and set its state high initially. let mut io = Io::new(peripherals.IO_MUX); io.set_interrupt_handler(handler); - let mut led = Output::new(peripherals.pins.gpio2, Level::Low); + let mut led = Output::new(peripherals.GPIO2, Level::Low); cfg_if::cfg_if! { if #[cfg(any(feature = "esp32", feature = "esp32s2", feature = "esp32s3"))] { - let button = peripherals.pins.gpio0; + let button = peripherals.GPIO0; } else { - let button = peripherals.pins.gpio9; + let button = peripherals.GPIO9; } } diff --git a/examples/src/bin/hello_world.rs b/examples/src/bin/hello_world.rs index 4e97c5d5353..a90ebb234c2 100644 --- a/examples/src/bin/hello_world.rs +++ b/examples/src/bin/hello_world.rs @@ -26,17 +26,17 @@ fn main() -> ! { // Default pins for Uart/Serial communication cfg_if::cfg_if! { if #[cfg(feature = "esp32")] { - let (mut tx_pin, mut rx_pin) = (peripherals.pins.gpio1, peripherals.pins.gpio3); + let (mut tx_pin, mut rx_pin) = (peripherals.GPIO1, peripherals.GPIO3); } else if #[cfg(feature = "esp32c2")] { - let (mut tx_pin, mut rx_pin) = (peripherals.pins.gpio20, peripherals.pins.gpio19); + let (mut tx_pin, mut rx_pin) = (peripherals.GPIO20, peripherals.GPIO19); } else if #[cfg(feature = "esp32c3")] { - let (mut tx_pin, mut rx_pin) = (peripherals.pins.gpio21, peripherals.pins.gpio20); + let (mut tx_pin, mut rx_pin) = (peripherals.GPIO21, peripherals.GPIO20); } else if #[cfg(feature = "esp32c6")] { - let (mut tx_pin, mut rx_pin) = (peripherals.pins.gpio16, peripherals.pins.gpio17); + let (mut tx_pin, mut rx_pin) = (peripherals.GPIO16, peripherals.GPIO17); } else if #[cfg(feature = "esp32h2")] { - let (mut tx_pin, mut rx_pin) = (peripherals.pins.gpio24, peripherals.pins.gpio23); + let (mut tx_pin, mut rx_pin) = (peripherals.GPIO24, peripherals.GPIO23); } else if #[cfg(any(feature = "esp32s2", feature = "esp32s3"))] { - let (mut tx_pin, mut rx_pin) = (peripherals.pins.gpio43, peripherals.pins.gpio44); + let (mut tx_pin, mut rx_pin) = (peripherals.GPIO43, peripherals.GPIO44); } } diff --git a/examples/src/bin/i2c_bmp180_calibration_data.rs b/examples/src/bin/i2c_bmp180_calibration_data.rs index b84536e7275..2d765fc31c2 100644 --- a/examples/src/bin/i2c_bmp180_calibration_data.rs +++ b/examples/src/bin/i2c_bmp180_calibration_data.rs @@ -25,8 +25,8 @@ fn main() -> ! { // Create a new peripheral object with the described wiring and standard // I2C clock speed: let mut i2c = I2c::new(peripherals.I2C0, Config::default()) - .with_sda(peripherals.pins.gpio4) - .with_scl(peripherals.pins.gpio5); + .with_sda(peripherals.GPIO4) + .with_scl(peripherals.GPIO5); loop { let mut data = [0u8; 22]; diff --git a/examples/src/bin/i2c_display.rs b/examples/src/bin/i2c_display.rs index 401c31b9378..c950def05fb 100644 --- a/examples/src/bin/i2c_display.rs +++ b/examples/src/bin/i2c_display.rs @@ -38,8 +38,8 @@ fn main() -> ! { // Create a new peripheral object with the described wiring // and standard I2C clock speed let i2c = I2c::new(peripherals.I2C0, Config::default()) - .with_sda(peripherals.pins.gpio4) - .with_scl(peripherals.pins.gpio5); + .with_sda(peripherals.GPIO4) + .with_scl(peripherals.GPIO5); // Initialize display let interface = I2CDisplayInterface::new(i2c); diff --git a/examples/src/bin/i2s_parallel.rs b/examples/src/bin/i2s_parallel.rs index fcfe88e9135..5f1bd400a3f 100644 --- a/examples/src/bin/i2s_parallel.rs +++ b/examples/src/bin/i2s_parallel.rs @@ -36,17 +36,17 @@ fn main() -> ! { let dma_channel = dma.i2s1channel; let i2s = peripherals.I2S1; - let clock = peripherals.pins.gpio25; + let clock = peripherals.GPIO25; let pins = TxEightBits::new( - peripherals.pins.gpio16, - peripherals.pins.gpio4, - peripherals.pins.gpio17, - peripherals.pins.gpio18, - peripherals.pins.gpio5, - peripherals.pins.gpio19, - peripherals.pins.gpio12, - peripherals.pins.gpio14, + peripherals.GPIO16, + peripherals.GPIO4, + peripherals.GPIO17, + peripherals.GPIO18, + peripherals.GPIO5, + peripherals.GPIO19, + peripherals.GPIO12, + peripherals.GPIO14, ); let (_, _, tx_buffer, tx_descriptors) = dma_buffers!(0, BUFFER_SIZE); diff --git a/examples/src/bin/i2s_read.rs b/examples/src/bin/i2s_read.rs index e9f1e3c7bdb..6697053cedb 100644 --- a/examples/src/bin/i2s_read.rs +++ b/examples/src/bin/i2s_read.rs @@ -52,13 +52,13 @@ fn main() -> ! { ); #[cfg(not(feature = "esp32"))] - let i2s = i2s.with_mclk(peripherals.pins.gpio0); + let i2s = i2s.with_mclk(peripherals.GPIO0); let mut i2s_rx = i2s .i2s_rx - .with_bclk(peripherals.pins.gpio2) - .with_ws(peripherals.pins.gpio4) - .with_din(peripherals.pins.gpio5) + .with_bclk(peripherals.GPIO2) + .with_ws(peripherals.GPIO4) + .with_din(peripherals.GPIO5) .build(); let mut transfer = i2s_rx.read_dma_circular(&mut rx_buffer).unwrap(); diff --git a/examples/src/bin/i2s_sound.rs b/examples/src/bin/i2s_sound.rs index 3d763490a04..de24c709b18 100644 --- a/examples/src/bin/i2s_sound.rs +++ b/examples/src/bin/i2s_sound.rs @@ -70,9 +70,9 @@ fn main() -> ! { let mut i2s_tx = i2s .i2s_tx - .with_bclk(peripherals.pins.gpio2) - .with_ws(peripherals.pins.gpio4) - .with_dout(peripherals.pins.gpio5) + .with_bclk(peripherals.GPIO2) + .with_ws(peripherals.GPIO4) + .with_dout(peripherals.GPIO5) .build(); let data = diff --git a/examples/src/bin/ieee802154_sniffer.rs b/examples/src/bin/ieee802154_sniffer.rs index 7e9663d2624..55b8d29afbe 100644 --- a/examples/src/bin/ieee802154_sniffer.rs +++ b/examples/src/bin/ieee802154_sniffer.rs @@ -19,9 +19,9 @@ fn main() -> ! { // Default pins for Uart/Serial communication cfg_if::cfg_if! { if #[cfg(feature = "esp32c6")] { - let (mut tx_pin, mut rx_pin) = (peripherals.pins.gpio16, peripherals.pins.gpio17); + let (mut tx_pin, mut rx_pin) = (peripherals.GPIO16, peripherals.GPIO17); } else if #[cfg(feature = "esp32h2")] { - let (mut tx_pin, mut rx_pin) = (peripherals.pins.gpio24, peripherals.pins.gpio23); + let (mut tx_pin, mut rx_pin) = (peripherals.GPIO24, peripherals.GPIO23); } } diff --git a/examples/src/bin/lcd_cam_ov2640.rs b/examples/src/bin/lcd_cam_ov2640.rs index 705ae915184..4a419a5d3f2 100644 --- a/examples/src/bin/lcd_cam_ov2640.rs +++ b/examples/src/bin/lcd_cam_ov2640.rs @@ -52,21 +52,21 @@ fn main() -> ! { let channel = channel.configure(false, DmaPriority::Priority0); - let cam_siod = peripherals.pins.gpio4; - let cam_sioc = peripherals.pins.gpio5; - let cam_xclk = peripherals.pins.gpio15; - let cam_vsync = peripherals.pins.gpio6; - let cam_href = peripherals.pins.gpio7; - let cam_pclk = peripherals.pins.gpio13; + let cam_siod = peripherals.GPIO4; + let cam_sioc = peripherals.GPIO5; + let cam_xclk = peripherals.GPIO15; + let cam_vsync = peripherals.GPIO6; + let cam_href = peripherals.GPIO7; + let cam_pclk = peripherals.GPIO13; let cam_data_pins = RxEightBits::new( - peripherals.pins.gpio11, - peripherals.pins.gpio9, - peripherals.pins.gpio8, - peripherals.pins.gpio10, - peripherals.pins.gpio12, - peripherals.pins.gpio18, - peripherals.pins.gpio17, - peripherals.pins.gpio16, + peripherals.GPIO11, + peripherals.GPIO9, + peripherals.GPIO8, + peripherals.GPIO10, + peripherals.GPIO12, + peripherals.GPIO18, + peripherals.GPIO17, + peripherals.GPIO16, ); let lcd_cam = LcdCam::new(peripherals.LCD_CAM); diff --git a/examples/src/bin/lcd_i8080.rs b/examples/src/bin/lcd_i8080.rs index 9c2c9c96921..749c5a546ee 100644 --- a/examples/src/bin/lcd_i8080.rs +++ b/examples/src/bin/lcd_i8080.rs @@ -41,11 +41,11 @@ use esp_println::println; fn main() -> ! { let peripherals = esp_hal::init(esp_hal::Config::default()); - let lcd_backlight = peripherals.pins.gpio45; - let lcd_reset = peripherals.pins.gpio4; - let lcd_rs = peripherals.pins.gpio0; // Command/Data selection - let lcd_wr = peripherals.pins.gpio47; // Write clock - let lcd_te = peripherals.pins.gpio48; // Frame sync + let lcd_backlight = peripherals.GPIO45; + let lcd_reset = peripherals.GPIO4; + let lcd_rs = peripherals.GPIO0; // Command/Data selection + let lcd_wr = peripherals.GPIO47; // Write clock + let lcd_te = peripherals.GPIO48; // Frame sync let dma = Dma::new(peripherals.DMA); let channel = dma.channel0; @@ -61,14 +61,14 @@ fn main() -> ! { let tear_effect = Input::new(lcd_te, Pull::None); let tx_pins = TxEightBits::new( - peripherals.pins.gpio9, - peripherals.pins.gpio46, - peripherals.pins.gpio3, - peripherals.pins.gpio8, - peripherals.pins.gpio18, - peripherals.pins.gpio17, - peripherals.pins.gpio16, - peripherals.pins.gpio15, + peripherals.GPIO9, + peripherals.GPIO46, + peripherals.GPIO3, + peripherals.GPIO8, + peripherals.GPIO18, + peripherals.GPIO17, + peripherals.GPIO16, + peripherals.GPIO15, ); let lcd_cam = LcdCam::new(peripherals.LCD_CAM); diff --git a/examples/src/bin/ledc.rs b/examples/src/bin/ledc.rs index 396065fb5ac..ce7b3bdd78a 100644 --- a/examples/src/bin/ledc.rs +++ b/examples/src/bin/ledc.rs @@ -25,7 +25,7 @@ use esp_hal::{ fn main() -> ! { let peripherals = esp_hal::init(esp_hal::Config::default()); - let led = peripherals.pins.gpio0; + let led = peripherals.GPIO0; let mut ledc = Ledc::new(peripherals.LEDC); diff --git a/examples/src/bin/lp_core_basic.rs b/examples/src/bin/lp_core_basic.rs index 56925e18adf..b26acf09107 100644 --- a/examples/src/bin/lp_core_basic.rs +++ b/examples/src/bin/lp_core_basic.rs @@ -27,7 +27,7 @@ fn main() -> ! { // configure GPIO 1 as LP output pin - let lp_pin = LowPowerOutput::new(peripherals.pins.gpio1); + let lp_pin = LowPowerOutput::new(peripherals.GPIO1); let mut lp_core = LpCore::new(peripherals.LP_CORE); lp_core.stop(); diff --git a/examples/src/bin/lp_core_i2c.rs b/examples/src/bin/lp_core_i2c.rs index 303b13a4499..c3bbe3c6bcc 100644 --- a/examples/src/bin/lp_core_i2c.rs +++ b/examples/src/bin/lp_core_i2c.rs @@ -27,8 +27,8 @@ use esp_println::println; fn main() -> ! { let peripherals = esp_hal::init(esp_hal::Config::default()); - let lp_sda = LowPowerOutputOpenDrain::new(peripherals.pins.gpio6); - let lp_scl = LowPowerOutputOpenDrain::new(peripherals.pins.gpio7); + let lp_sda = LowPowerOutputOpenDrain::new(peripherals.GPIO6); + let lp_scl = LowPowerOutputOpenDrain::new(peripherals.GPIO7); let lp_i2c = LpI2c::new(peripherals.LP_I2C0, lp_sda, lp_scl, 100.kHz()); diff --git a/examples/src/bin/lp_core_uart.rs b/examples/src/bin/lp_core_uart.rs index b3cbc7df67c..15c3d98da71 100644 --- a/examples/src/bin/lp_core_uart.rs +++ b/examples/src/bin/lp_core_uart.rs @@ -32,14 +32,14 @@ fn main() -> ! { let mut uart1 = Uart::new_with_config( peripherals.UART1, Config::default(), - peripherals.pins.gpio6, - peripherals.pins.gpio7, + peripherals.GPIO6, + peripherals.GPIO7, ) .unwrap(); // Set up (LP) UART: - let lp_tx = LowPowerOutput::new(peripherals.pins.gpio5); - let lp_rx = LowPowerInput::new(peripherals.pins.gpio4); + let lp_tx = LowPowerOutput::new(peripherals.GPIO5); + let lp_rx = LowPowerInput::new(peripherals.GPIO4); let lp_uart = LpUart::new(peripherals.LP_UART, lp_tx, lp_rx); let mut lp_core = LpCore::new(peripherals.LP_CORE); diff --git a/examples/src/bin/mcpwm.rs b/examples/src/bin/mcpwm.rs index 98d42bdeb99..8e3281159e9 100644 --- a/examples/src/bin/mcpwm.rs +++ b/examples/src/bin/mcpwm.rs @@ -19,7 +19,7 @@ use esp_hal::{ fn main() -> ! { let peripherals = esp_hal::init(esp_hal::Config::default()); - let pin = peripherals.pins.gpio0; + let pin = peripherals.GPIO0; // initialize peripheral cfg_if::cfg_if! { diff --git a/examples/src/bin/parl_io_rx.rs b/examples/src/bin/parl_io_rx.rs index 22937190c2c..6f5d1c2f353 100644 --- a/examples/src/bin/parl_io_rx.rs +++ b/examples/src/bin/parl_io_rx.rs @@ -29,10 +29,10 @@ fn main() -> ! { let dma_channel = dma.channel0; let mut rx_pins = RxFourBits::new( - peripherals.pins.gpio1, - peripherals.pins.gpio2, - peripherals.pins.gpio3, - peripherals.pins.gpio4, + peripherals.GPIO1, + peripherals.GPIO2, + peripherals.GPIO3, + peripherals.GPIO4, ); let parl_io = ParlIoRxOnly::new( diff --git a/examples/src/bin/parl_io_tx.rs b/examples/src/bin/parl_io_tx.rs index 97184a339fd..fc790349e78 100644 --- a/examples/src/bin/parl_io_tx.rs +++ b/examples/src/bin/parl_io_tx.rs @@ -40,13 +40,13 @@ fn main() -> ! { let dma_channel = dma.channel0; let tx_pins = TxFourBits::new( - peripherals.pins.gpio1, - peripherals.pins.gpio2, - peripherals.pins.gpio3, - peripherals.pins.gpio4, + peripherals.GPIO1, + peripherals.GPIO2, + peripherals.GPIO3, + peripherals.GPIO4, ); - let mut pin_conf = TxPinConfigWithValidPin::new(tx_pins, peripherals.pins.gpio5); + let mut pin_conf = TxPinConfigWithValidPin::new(tx_pins, peripherals.GPIO5); let parl_io = ParlIoTxOnly::new( peripherals.PARL_IO, @@ -56,7 +56,7 @@ fn main() -> ! { ) .unwrap(); - let mut clock_pin = ClkOutPin::new(peripherals.pins.gpio6); + let mut clock_pin = ClkOutPin::new(peripherals.GPIO6); let mut parl_io_tx = parl_io .tx diff --git a/examples/src/bin/pcnt_encoder.rs b/examples/src/bin/pcnt_encoder.rs index 4c5ee1cf0ee..29a9a1a6b20 100644 --- a/examples/src/bin/pcnt_encoder.rs +++ b/examples/src/bin/pcnt_encoder.rs @@ -48,8 +48,8 @@ fn main() -> ! { println!("setup channel 0"); let ch0 = &u0.channel0; - let pin_a = Input::new(peripherals.pins.gpio4, Pull::Up); - let pin_b = Input::new(peripherals.pins.gpio5, Pull::Up); + let pin_a = Input::new(peripherals.GPIO4, Pull::Up); + let pin_b = Input::new(peripherals.GPIO5, Pull::Up); let (input_a, _) = pin_a.split(); let (input_b, _) = pin_b.split(); diff --git a/examples/src/bin/qspi_flash.rs b/examples/src/bin/qspi_flash.rs index e2bea23632c..a7e9df83b54 100644 --- a/examples/src/bin/qspi_flash.rs +++ b/examples/src/bin/qspi_flash.rs @@ -47,19 +47,19 @@ fn main() -> ! { cfg_if::cfg_if! { if #[cfg(feature = "esp32")] { - let sclk = peripherals.pins.gpio0; - let miso = peripherals.pins.gpio2; - let mosi = peripherals.pins.gpio4; - let sio2 = peripherals.pins.gpio5; - let sio3 = peripherals.pins.gpio13; - let cs = peripherals.pins.gpio14; + let sclk = peripherals.GPIO0; + let miso = peripherals.GPIO2; + let mosi = peripherals.GPIO4; + let sio2 = peripherals.GPIO5; + let sio3 = peripherals.GPIO13; + let cs = peripherals.GPIO14; } else { - let sclk = peripherals.pins.gpio0; - let miso = peripherals.pins.gpio1; - let mosi = peripherals.pins.gpio2; - let sio2 = peripherals.pins.gpio3; - let sio3 = peripherals.pins.gpio4; - let cs = peripherals.pins.gpio5; + let sclk = peripherals.GPIO0; + let miso = peripherals.GPIO1; + let mosi = peripherals.GPIO2; + let sio2 = peripherals.GPIO3; + let sio3 = peripherals.GPIO4; + let cs = peripherals.GPIO5; } } diff --git a/examples/src/bin/rmt_rx.rs b/examples/src/bin/rmt_rx.rs index 1e35cea7ade..c9dc626b1b4 100644 --- a/examples/src/bin/rmt_rx.rs +++ b/examples/src/bin/rmt_rx.rs @@ -26,7 +26,7 @@ const WIDTH: usize = 80; fn main() -> ! { let peripherals = esp_hal::init(esp_hal::Config::default()); - let mut out = Output::new(peripherals.pins.gpio5, Level::Low); + let mut out = Output::new(peripherals.GPIO5, Level::Low); cfg_if::cfg_if! { if #[cfg(feature = "esp32h2")] { @@ -46,11 +46,11 @@ fn main() -> ! { cfg_if::cfg_if! { if #[cfg(any(feature = "esp32", feature = "esp32s2"))] { - let mut channel = rmt.channel0.configure(peripherals.pins.gpio4, rx_config).unwrap(); + let mut channel = rmt.channel0.configure(peripherals.GPIO4, rx_config).unwrap(); } else if #[cfg(feature = "esp32s3")] { - let mut channel = rmt.channel7.configure(peripherals.pins.gpio4, rx_config).unwrap(); + let mut channel = rmt.channel7.configure(peripherals.GPIO4, rx_config).unwrap(); } else { - let mut channel = rmt.channel2.configure(peripherals.pins.gpio4, rx_config).unwrap(); + let mut channel = rmt.channel2.configure(peripherals.GPIO4, rx_config).unwrap(); } } diff --git a/examples/src/bin/rmt_tx.rs b/examples/src/bin/rmt_tx.rs index c3ae58e996e..d87e8d87a85 100644 --- a/examples/src/bin/rmt_tx.rs +++ b/examples/src/bin/rmt_tx.rs @@ -38,7 +38,7 @@ fn main() -> ! { let mut channel = rmt .channel0 - .configure(peripherals.pins.gpio4, tx_config) + .configure(peripherals.GPIO4, tx_config) .unwrap(); let delay = Delay::new(); diff --git a/examples/src/bin/serial_interrupts.rs b/examples/src/bin/serial_interrupts.rs index a8dec11dcb7..725f5814d24 100644 --- a/examples/src/bin/serial_interrupts.rs +++ b/examples/src/bin/serial_interrupts.rs @@ -29,17 +29,17 @@ fn main() -> ! { // Default pins for Uart/Serial communication cfg_if::cfg_if! { if #[cfg(feature = "esp32")] { - let (tx_pin, rx_pin) = (peripherals.pins.gpio1, peripherals.pins.gpio3); + let (tx_pin, rx_pin) = (peripherals.GPIO1, peripherals.GPIO3); } else if #[cfg(feature = "esp32c2")] { - let (tx_pin, rx_pin) = (peripherals.pins.gpio20, peripherals.pins.gpio19); + let (tx_pin, rx_pin) = (peripherals.GPIO20, peripherals.GPIO19); } else if #[cfg(feature = "esp32c3")] { - let (tx_pin, rx_pin) = (peripherals.pins.gpio21, peripherals.pins.gpio20); + let (tx_pin, rx_pin) = (peripherals.GPIO21, peripherals.GPIO20); } else if #[cfg(feature = "esp32c6")] { - let (tx_pin, rx_pin) = (peripherals.pins.gpio16, peripherals.pins.gpio17); + let (tx_pin, rx_pin) = (peripherals.GPIO16, peripherals.GPIO17); } else if #[cfg(feature = "esp32h2")] { - let (tx_pin, rx_pin) = (peripherals.pins.gpio24, peripherals.pins.gpio23); + let (tx_pin, rx_pin) = (peripherals.GPIO24, peripherals.GPIO23); } else if #[cfg(any(feature = "esp32s2", feature = "esp32s3"))] { - let (tx_pin, rx_pin) = (peripherals.pins.gpio43, peripherals.pins.gpio44); + let (tx_pin, rx_pin) = (peripherals.GPIO43, peripherals.GPIO44); } } let config = Config::default().rx_fifo_full_threshold(30); diff --git a/examples/src/bin/sleep_timer_ext0.rs b/examples/src/bin/sleep_timer_ext0.rs index 77d0bfab3b2..f026bbc68b1 100644 --- a/examples/src/bin/sleep_timer_ext0.rs +++ b/examples/src/bin/sleep_timer_ext0.rs @@ -32,7 +32,7 @@ fn main() -> ! { let mut rtc = Rtc::new(peripherals.LPWR); - let ext0_pin = Input::new(peripherals.pins.gpio4, Pull::None); + let ext0_pin = Input::new(peripherals.GPIO4, Pull::None); println!("up and runnning!"); let reason = get_reset_reason(Cpu::ProCpu).unwrap_or(SocResetReason::ChipPowerOn); diff --git a/examples/src/bin/sleep_timer_ext1.rs b/examples/src/bin/sleep_timer_ext1.rs index ba764fac968..783a4a26af7 100644 --- a/examples/src/bin/sleep_timer_ext1.rs +++ b/examples/src/bin/sleep_timer_ext1.rs @@ -33,8 +33,8 @@ fn main() -> ! { let mut rtc = Rtc::new(peripherals.LPWR); - let pin_0 = Input::new(peripherals.pins.gpio4, Pull::None); - let mut pin_2 = peripherals.pins.gpio2; + let pin_0 = Input::new(peripherals.GPIO4, Pull::None); + let mut pin_2 = peripherals.GPIO2; println!("up and runnning!"); let reason = get_reset_reason(Cpu::ProCpu).unwrap_or(SocResetReason::ChipPowerOn); diff --git a/examples/src/bin/sleep_timer_lpio.rs b/examples/src/bin/sleep_timer_lpio.rs index cc449228a35..8ae16d28eb4 100644 --- a/examples/src/bin/sleep_timer_lpio.rs +++ b/examples/src/bin/sleep_timer_lpio.rs @@ -34,8 +34,8 @@ fn main() -> ! { let mut rtc = Rtc::new(peripherals.LPWR); - let pin2 = Input::new(peripherals.pins.gpio2, Pull::None); - let mut pin3 = peripherals.pins.gpio3; + let pin2 = Input::new(peripherals.GPIO2, Pull::None); + let mut pin3 = peripherals.GPIO3; println!("up and runnning!"); let reason = get_reset_reason(Cpu::ProCpu).unwrap_or(SocResetReason::ChipPowerOn); diff --git a/examples/src/bin/sleep_timer_rtcio.rs b/examples/src/bin/sleep_timer_rtcio.rs index c87f22eba86..a04c7892ecb 100644 --- a/examples/src/bin/sleep_timer_rtcio.rs +++ b/examples/src/bin/sleep_timer_rtcio.rs @@ -49,16 +49,16 @@ fn main() -> ! { cfg_if::cfg_if! { if #[cfg(any(feature = "esp32c3", feature = "esp32c2"))] { - let pin2 = Input::new(peripherals.pins.gpio2, Pull::None); - let mut pin3 = peripherals.pins.gpio3; + let pin2 = Input::new(peripherals.GPIO2, Pull::None); + let mut pin3 = peripherals.GPIO3; let wakeup_pins: &mut [(&mut dyn gpio::RtcPinWithResistors, WakeupLevel)] = &mut [ (&mut *pin2.into_ref(), WakeupLevel::Low), (&mut pin3, WakeupLevel::High), ]; } else if #[cfg(feature = "esp32s3")] { - let pin17 = Input::new(peripherals.pins.gpio17, Pull::None); - let mut pin18 = peripherals.pins.gpio18; + let pin17 = Input::new(peripherals.GPIO17, Pull::None); + let mut pin18 = peripherals.GPIO18; let wakeup_pins: &mut [(&mut dyn gpio::RtcPin, WakeupLevel)] = &mut [ (&mut *pin17.into_ref(), WakeupLevel::Low), diff --git a/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs b/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs index 5ee15877be3..6ea46778f86 100644 --- a/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs +++ b/examples/src/bin/spi_halfduplex_read_manufacturer_id.rs @@ -45,19 +45,19 @@ fn main() -> ! { cfg_if::cfg_if! { if #[cfg(feature = "esp32")] { - let sclk = peripherals.pins.gpio0; - let miso = peripherals.pins.gpio2; - let mosi = peripherals.pins.gpio4; - let sio2 = peripherals.pins.gpio5; - let sio3 = peripherals.pins.gpio13; - let cs = peripherals.pins.gpio14; + let sclk = peripherals.GPIO0; + let miso = peripherals.GPIO2; + let mosi = peripherals.GPIO4; + let sio2 = peripherals.GPIO5; + let sio3 = peripherals.GPIO13; + let cs = peripherals.GPIO14; } else { - let sclk = peripherals.pins.gpio0; - let miso = peripherals.pins.gpio1; - let mosi = peripherals.pins.gpio2; - let sio2 = peripherals.pins.gpio3; - let sio3 = peripherals.pins.gpio4; - let cs = peripherals.pins.gpio5; + let sclk = peripherals.GPIO0; + let miso = peripherals.GPIO1; + let mosi = peripherals.GPIO2; + let sio2 = peripherals.GPIO3; + let sio3 = peripherals.GPIO4; + let cs = peripherals.GPIO5; } } diff --git a/examples/src/bin/spi_loopback.rs b/examples/src/bin/spi_loopback.rs index 577b1a821c0..22e92a29ca5 100644 --- a/examples/src/bin/spi_loopback.rs +++ b/examples/src/bin/spi_loopback.rs @@ -31,9 +31,9 @@ use esp_println::println; fn main() -> ! { let peripherals = esp_hal::init(esp_hal::Config::default()); - let sclk = peripherals.pins.gpio0; - let miso_mosi = peripherals.pins.gpio2; - let cs = peripherals.pins.gpio5; + let sclk = peripherals.GPIO0; + let miso_mosi = peripherals.GPIO2; + let cs = peripherals.GPIO5; let miso = unsafe { miso_mosi.clone_unchecked() }; diff --git a/examples/src/bin/spi_loopback_dma.rs b/examples/src/bin/spi_loopback_dma.rs index 8dcb339078a..639ac030927 100644 --- a/examples/src/bin/spi_loopback_dma.rs +++ b/examples/src/bin/spi_loopback_dma.rs @@ -35,10 +35,10 @@ use esp_println::println; fn main() -> ! { let peripherals = esp_hal::init(esp_hal::Config::default()); - let sclk = peripherals.pins.gpio0; - let miso = peripherals.pins.gpio2; - let mosi = peripherals.pins.gpio4; - let cs = peripherals.pins.gpio5; + let sclk = peripherals.GPIO0; + let miso = peripherals.GPIO2; + let mosi = peripherals.GPIO4; + let cs = peripherals.GPIO5; let dma = Dma::new(peripherals.DMA); diff --git a/examples/src/bin/spi_loopback_dma_psram.rs b/examples/src/bin/spi_loopback_dma_psram.rs index 10c077b9420..0a8fe54445b 100644 --- a/examples/src/bin/spi_loopback_dma_psram.rs +++ b/examples/src/bin/spi_loopback_dma_psram.rs @@ -62,10 +62,10 @@ fn main() -> ! { esp_alloc::psram_allocator!(peripherals.PSRAM, esp_hal::psram); let delay = Delay::new(); - let sclk = peripherals.pins.gpio42; - let mosi = peripherals.pins.gpio48; + let sclk = peripherals.GPIO42; + let mosi = peripherals.GPIO48; let miso = unsafe { mosi.clone_unchecked() }; - let cs = peripherals.pins.gpio38; + let cs = peripherals.GPIO38; let dma = Dma::new(peripherals.DMA); let dma_channel = dma.channel0; diff --git a/examples/src/bin/spi_slave_dma.rs b/examples/src/bin/spi_slave_dma.rs index 29c64356373..142816166f9 100644 --- a/examples/src/bin/spi_slave_dma.rs +++ b/examples/src/bin/spi_slave_dma.rs @@ -44,15 +44,15 @@ use esp_println::println; fn main() -> ! { let peripherals = esp_hal::init(esp_hal::Config::default()); - let mut master_sclk = Output::new(peripherals.pins.gpio4, Level::Low); - let master_miso = Input::new(peripherals.pins.gpio5, Pull::None); - let mut master_mosi = Output::new(peripherals.pins.gpio8, Level::Low); - let mut master_cs = Output::new(peripherals.pins.gpio9, Level::High); - - let slave_sclk = peripherals.pins.gpio0; - let slave_miso = peripherals.pins.gpio1; - let slave_mosi = peripherals.pins.gpio2; - let slave_cs = peripherals.pins.gpio3; + let mut master_sclk = Output::new(peripherals.GPIO4, Level::Low); + let master_miso = Input::new(peripherals.GPIO5, Pull::None); + let mut master_mosi = Output::new(peripherals.GPIO8, Level::Low); + let mut master_cs = Output::new(peripherals.GPIO9, Level::High); + + let slave_sclk = peripherals.GPIO0; + let slave_miso = peripherals.GPIO1; + let slave_mosi = peripherals.GPIO2; + let slave_cs = peripherals.GPIO3; let dma = Dma::new(peripherals.DMA); cfg_if::cfg_if! { diff --git a/examples/src/bin/touch.rs b/examples/src/bin/touch.rs index d82a794df70..a36207a8a75 100644 --- a/examples/src/bin/touch.rs +++ b/examples/src/bin/touch.rs @@ -52,8 +52,8 @@ fn main() -> ! { let mut rtc = Rtc::new(peripherals.LPWR); rtc.set_interrupt_handler(interrupt_handler); - let touch_pin0 = peripherals.pins.gpio2; - let touch_pin1 = peripherals.pins.gpio4; + let touch_pin0 = peripherals.GPIO2; + let touch_pin1 = peripherals.GPIO4; let touch_cfg = Some(TouchConfig { measurement_duration: Some(0x2000), diff --git a/examples/src/bin/twai.rs b/examples/src/bin/twai.rs index 063d6c1d7bb..b59a39cda55 100644 --- a/examples/src/bin/twai.rs +++ b/examples/src/bin/twai.rs @@ -40,10 +40,10 @@ fn main() -> ! { let peripherals = esp_hal::init(esp_hal::Config::default()); // Without an external transceiver, we only need a single line between the two MCUs. - let (rx_pin, tx_pin) = peripherals.pins.gpio2.split(); + let (rx_pin, tx_pin) = peripherals.GPIO2.split(); // Use these if you want to use an external transceiver: - // let tx_pin = peripherals.pins.gpio2; - // let rx_pin = peripherals.pins.gpio0; + // let tx_pin = peripherals.GPIO2; + // let rx_pin = peripherals.GPIO0; // The speed of the bus. const TWAI_BAUDRATE: twai::BaudRate = twai::BaudRate::B125K; diff --git a/examples/src/bin/ulp_riscv_core_basic.rs b/examples/src/bin/ulp_riscv_core_basic.rs index 98087c84d54..6d062b7f3c1 100644 --- a/examples/src/bin/ulp_riscv_core_basic.rs +++ b/examples/src/bin/ulp_riscv_core_basic.rs @@ -19,7 +19,7 @@ use esp_println::{print, println}; fn main() -> ! { let peripherals = esp_hal::init(esp_hal::Config::default()); - let pin = LowPowerOutput::new(peripherals.pins.gpio1); + let pin = LowPowerOutput::new(peripherals.GPIO1); let mut ulp_core = ulp_core::UlpCore::new(peripherals.ULP_RISCV_CORE); diff --git a/examples/src/bin/usb_serial.rs b/examples/src/bin/usb_serial.rs index 8f29eaa71ca..ac29552b40f 100644 --- a/examples/src/bin/usb_serial.rs +++ b/examples/src/bin/usb_serial.rs @@ -29,8 +29,8 @@ fn main() -> ! { let usb = Usb::new( peripherals.USB0, - peripherals.pins.gpio20, - peripherals.pins.gpio19, + peripherals.GPIO20, + peripherals.GPIO19, ); let usb_bus = UsbBus::new(usb, unsafe { &mut *addr_of_mut!(EP_MEMORY) }); diff --git a/examples/src/bin/wifi_ble.rs b/examples/src/bin/wifi_ble.rs index 4927f6d0fde..84e383e0787 100644 --- a/examples/src/bin/wifi_ble.rs +++ b/examples/src/bin/wifi_ble.rs @@ -56,9 +56,9 @@ fn main() -> ! { cfg_if::cfg_if! { if #[cfg(any(feature = "esp32", feature = "esp32s2", feature = "esp32s3"))] { - let button = Input::new(peripherals.pins.gpio0, Pull::Down); + let button = Input::new(peripherals.GPIO0, Pull::Down); } else { - let button = Input::new(peripherals.pins.gpio9, Pull::Down); + let button = Input::new(peripherals.GPIO9, Pull::Down); } } diff --git a/examples/src/bin/wifi_embassy_ble.rs b/examples/src/bin/wifi_embassy_ble.rs index a303c2b7cc9..22ad06076d4 100644 --- a/examples/src/bin/wifi_embassy_ble.rs +++ b/examples/src/bin/wifi_embassy_ble.rs @@ -72,9 +72,9 @@ async fn main(_spawner: Spawner) -> ! { cfg_if::cfg_if! { if #[cfg(any(feature = "esp32", feature = "esp32s2", feature = "esp32s3"))] { - let button = Input::new(peripherals.pins.gpio0, Pull::Down); + let button = Input::new(peripherals.GPIO0, Pull::Down); } else { - let button = Input::new(peripherals.pins.gpio9, Pull::Down); + let button = Input::new(peripherals.GPIO9, Pull::Down); } } diff --git a/hil-test/src/lib.rs b/hil-test/src/lib.rs index 04fd7f6e9c4..660e8697cbe 100644 --- a/hil-test/src/lib.rs +++ b/hil-test/src/lib.rs @@ -31,17 +31,17 @@ macro_rules! i2c_pins { // Order: (SDA, SCL) cfg_if::cfg_if! { if #[cfg(any(esp32s2, esp32s3))] { - ($peripherals.pins.gpio2, $peripherals.pins.gpio3) + ($peripherals.GPIO2, $peripherals.GPIO3) } else if #[cfg(esp32)] { - ($peripherals.pins.gpio32, $peripherals.pins.gpio33) + ($peripherals.GPIO32, $peripherals.GPIO33) } else if #[cfg(esp32c6)] { - ($peripherals.pins.gpio6, $peripherals.pins.gpio7) + ($peripherals.GPIO6, $peripherals.GPIO7) } else if #[cfg(esp32h2)] { - ($peripherals.pins.gpio12, $peripherals.pins.gpio22) + ($peripherals.GPIO12, $peripherals.GPIO22) } else if #[cfg(esp32c2)] { - ($peripherals.pins.gpio18, $peripherals.pins.gpio9) + ($peripherals.GPIO18, $peripherals.GPIO9) } else { - ($peripherals.pins.gpio4, $peripherals.pins.gpio5) + ($peripherals.GPIO4, $peripherals.GPIO5) } } }}; @@ -52,11 +52,11 @@ macro_rules! common_test_pins { ($peripherals:expr) => {{ cfg_if::cfg_if! { if #[cfg(any(esp32s2, esp32s3))] { - ($peripherals.pins.gpio9, $peripherals.pins.gpio10) + ($peripherals.GPIO9, $peripherals.GPIO10) } else if #[cfg(esp32)] { - ($peripherals.pins.gpio26, $peripherals.pins.gpio27) + ($peripherals.GPIO26, $peripherals.GPIO27) } else { - ($peripherals.pins.gpio2, $peripherals.pins.gpio3) + ($peripherals.GPIO2, $peripherals.GPIO3) } } }}; @@ -69,15 +69,15 @@ macro_rules! unconnected_pin { ($peripherals:expr) => {{ cfg_if::cfg_if! { if #[cfg(any(esp32, esp32s2, esp32s3))] { - $peripherals.pins.gpio0 + $peripherals.GPIO0 } else if #[cfg(esp32c6)] { - $peripherals.pins.gpio9 + $peripherals.GPIO9 } else if #[cfg(esp32h2)] { - $peripherals.pins.gpio9 + $peripherals.GPIO9 } else if #[cfg(esp32c2)] { - $peripherals.pins.gpio8 + $peripherals.GPIO8 } else { - $peripherals.pins.gpio9 + $peripherals.GPIO9 } } }}; diff --git a/hil-test/tests/embassy_interrupt_spi_dma.rs b/hil-test/tests/embassy_interrupt_spi_dma.rs index 46c91be1914..082fd2dceca 100644 --- a/hil-test/tests/embassy_interrupt_spi_dma.rs +++ b/hil-test/tests/embassy_interrupt_spi_dma.rs @@ -11,7 +11,6 @@ use embassy_time::{Duration, Instant, Ticker}; use esp_hal::{ dma::{Dma, DmaPriority, DmaRxBuf, DmaTxBuf}, dma_buffers, - gpio::Io, interrupt::{software::SoftwareInterruptControl, Priority}, peripheral::Peripheral, prelude::*, diff --git a/hil-test/tests/gpio.rs b/hil-test/tests/gpio.rs index 1d999fbf3bf..0d197b2d17d 100644 --- a/hil-test/tests/gpio.rs +++ b/hil-test/tests/gpio.rs @@ -387,8 +387,8 @@ mod tests { #[cfg(esp32)] #[test] fn can_configure_rtcio_pins_as_input() { - let pins = unsafe { esp_hal::gpio::Pins::steal() }; + let pin = unsafe { esp_hal::gpio::GpioPin::<37>::steal() }; - _ = Input::new(pins.gpio37, Pull::Down); + _ = Input::new(pin, Pull::Down); } } diff --git a/hil-test/tests/lcd_cam_i8080.rs b/hil-test/tests/lcd_cam_i8080.rs index 2c7d761ddbf..33a76d04c36 100644 --- a/hil-test/tests/lcd_cam_i8080.rs +++ b/hil-test/tests/lcd_cam_i8080.rs @@ -8,7 +8,7 @@ use esp_hal::{ dma::{Dma, DmaPriority, DmaTxBuf}, dma_buffers, - gpio::{Io, NoPin, Pins}, + gpio::{GpioPin, NoPin}, lcd_cam::{ lcd::i8080::{Command, Config, TxEightBits, TxSixteenBits, I8080}, BitOrder, @@ -25,6 +25,15 @@ use hil_test as _; const DATA_SIZE: usize = 1024 * 10; +#[allow(non_snake_case)] +struct Pins { + pub GPIO8: GpioPin<8>, + pub GPIO11: GpioPin<11>, + pub GPIO12: GpioPin<12>, + pub GPIO16: GpioPin<16>, + pub GPIO17: GpioPin<17>, +} + struct Context<'d> { lcd_cam: LcdCam<'d, Blocking>, pcnt: Pcnt<'d>, @@ -52,7 +61,13 @@ mod tests { lcd_cam, dma, pcnt, - pins: peripherals.pins, + pins: Pins { + GPIO8: peripherals.GPIO8, + GPIO11: peripherals.GPIO11, + GPIO12: peripherals.GPIO12, + GPIO16: peripherals.GPIO16, + GPIO17: peripherals.GPIO17, + }, dma_buf, } } @@ -102,11 +117,11 @@ mod tests { // issue with configuring pins as outputs after inputs have been sorted // out. See https://github.com/esp-rs/esp-hal/pull/2173#issue-2529323702 - let (unit_ctrl, cs_signal) = ctx.pins.gpio8.split(); - let (unit0_input, unit0_signal) = ctx.pins.gpio11.split(); - let (unit1_input, unit1_signal) = ctx.pins.gpio12.split(); - let (unit2_input, unit2_signal) = ctx.pins.gpio16.split(); - let (unit3_input, unit3_signal) = ctx.pins.gpio17.split(); + let (unit_ctrl, cs_signal) = ctx.pins.GPIO8.split(); + let (unit0_input, unit0_signal) = ctx.pins.GPIO11.split(); + let (unit1_input, unit1_signal) = ctx.pins.GPIO12.split(); + let (unit2_input, unit2_signal) = ctx.pins.GPIO16.split(); + let (unit3_input, unit3_signal) = ctx.pins.GPIO17.split(); let pcnt = ctx.pcnt; @@ -213,11 +228,11 @@ mod tests { // issue with configuring pins as outputs after inputs have been sorted // out. See https://github.com/esp-rs/esp-hal/pull/2173#issue-2529323702 - let (unit_ctrl, cs_signal) = ctx.pins.gpio8.split(); - let (unit0_input, unit0_signal) = ctx.pins.gpio11.split(); - let (unit1_input, unit1_signal) = ctx.pins.gpio12.split(); - let (unit2_input, unit2_signal) = ctx.pins.gpio16.split(); - let (unit3_input, unit3_signal) = ctx.pins.gpio17.split(); + let (unit_ctrl, cs_signal) = ctx.pins.GPIO8.split(); + let (unit0_input, unit0_signal) = ctx.pins.GPIO11.split(); + let (unit1_input, unit1_signal) = ctx.pins.GPIO12.split(); + let (unit2_input, unit2_signal) = ctx.pins.GPIO16.split(); + let (unit3_input, unit3_signal) = ctx.pins.GPIO17.split(); let pcnt = ctx.pcnt; diff --git a/hil-test/tests/spi_full_duplex.rs b/hil-test/tests/spi_full_duplex.rs index 7a0b0ea9570..3e7a42b398c 100644 --- a/hil-test/tests/spi_full_duplex.rs +++ b/hil-test/tests/spi_full_duplex.rs @@ -58,7 +58,7 @@ mod tests { fn init() -> Context { let peripherals = esp_hal::init(esp_hal::Config::default()); - let sclk = peripherals.pins.gpio0; + let sclk = peripherals.GPIO0; let (_, mosi) = hil_test::common_test_pins!(peripherals); let dma = Dma::new(peripherals.DMA); diff --git a/hil-test/tests/spi_half_duplex_read.rs b/hil-test/tests/spi_half_duplex_read.rs index 8192850293e..212e764424a 100644 --- a/hil-test/tests/spi_half_duplex_read.rs +++ b/hil-test/tests/spi_half_duplex_read.rs @@ -33,7 +33,7 @@ mod tests { fn init() -> Context { let peripherals = esp_hal::init(esp_hal::Config::default()); - let sclk = peripherals.pins.gpio0; + let sclk = peripherals.GPIO0; let (miso, miso_mirror) = hil_test::common_test_pins!(peripherals); let miso_mirror = Output::new(miso_mirror, Level::High); diff --git a/hil-test/tests/spi_half_duplex_write.rs b/hil-test/tests/spi_half_duplex_write.rs index 7ec44286c4b..985ede3e5f6 100644 --- a/hil-test/tests/spi_half_duplex_write.rs +++ b/hil-test/tests/spi_half_duplex_write.rs @@ -35,7 +35,7 @@ mod tests { fn init() -> Context { let peripherals = esp_hal::init(esp_hal::Config::default()); - let sclk = peripherals.pins.gpio0; + let sclk = peripherals.GPIO0; let (mosi, _) = hil_test::common_test_pins!(peripherals); let pcnt = Pcnt::new(peripherals.PCNT); diff --git a/hil-test/tests/spi_half_duplex_write_psram.rs b/hil-test/tests/spi_half_duplex_write_psram.rs index 6968ecb32f5..950cf2f0ea6 100644 --- a/hil-test/tests/spi_half_duplex_write_psram.rs +++ b/hil-test/tests/spi_half_duplex_write_psram.rs @@ -10,7 +10,7 @@ use esp_hal::{ dma::{Dma, DmaBufBlkSize, DmaPriority, DmaRxBuf, DmaTxBuf}, dma_buffers, dma_descriptors_chunk_size, - gpio::{interconnect::InputSignal, Io}, + gpio::interconnect::InputSignal, pcnt::{channel::EdgeMode, unit::Unit, Pcnt}, prelude::*, spi::{ @@ -53,7 +53,7 @@ mod tests { let peripherals = esp_hal::init(esp_hal::Config::default()); esp_alloc::psram_allocator!(peripherals.PSRAM, esp_hal::psram); - let sclk = peripherals.pins.gpio0; + let sclk = peripherals.GPIO0; let (mosi, _) = hil_test::common_test_pins!(peripherals); let pcnt = Pcnt::new(peripherals.PCNT);