Remove pins from Io (#2508)

* Split pins off of Io

* Remove the GPIO peripheral

* p.GPIO
This commit is contained in:
Dániel Buga 2024-11-12 11:36:25 +01:00 committed by GitHub
parent 321ca2f131
commit fbc57542a8
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
134 changed files with 1216 additions and 1428 deletions

View File

@ -171,6 +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)
### Fixed
@ -215,6 +216,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
- Removed `esp_hal::spi::slave::WithDmaSpiN` traits (#2260)
- The `WithDmaAes` trait has been removed (#2261)
- The `I2s::new_i2s1` constructor has been removed (#2261)
- `Peripherals.GPIO` has been removed (#2508)
## [0.20.1] - 2024-08-30

View File

@ -1,5 +1,23 @@
# Migration Guide from 0.21.x to v0.22.x
## IO changes
### GPIO pins are now accessible via `Peripherals`
```diff
let peripherals = esp_hal::init(Default::default());
-let io = Io::new(peripherals.GPIO, peripherals.IOMUX);
-let pin = io.pins.gpio5;
+let pin = peripherals.GPIO5;
```
### `Io` constructor changes
- `new_with_priority` and `new_no_bind_interrupts` have been removed.
Use `set_priority` to configure the GPIO interrupt priority.
We no longer overwrite interrupt handlers set by user code during initialization.
- `new` no longer takes `peripherals.GPIO`
## Removed `async`-specific constructors
The following async-specific constuctors have been removed:

View File

@ -31,13 +31,11 @@
//! # use esp_hal::analog::adc::Attenuation;
//! # use esp_hal::analog::adc::Adc;
//! # use esp_hal::delay::Delay;
//! # use esp_hal::gpio::Io;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
#![cfg_attr(esp32, doc = "let analog_pin = io.pins.gpio32;")]
#![cfg_attr(any(esp32s2, esp32s3), doc = "let analog_pin = io.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 = io.pins.gpio2;"
doc = "let analog_pin = peripherals.GPIO2;"
)]
//! let mut adc1_config = AdcConfig::new();
//! let mut pin = adc1_config.enable_pin(

View File

@ -17,14 +17,11 @@
//! ### Write a value to a DAC channel
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::gpio::Io;
//! # use esp_hal::analog::dac::Dac;
//! # use esp_hal::delay::Delay;
//! # use embedded_hal::delay::DelayNs;
//!
//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
#![cfg_attr(esp32, doc = "let dac1_pin = io.pins.gpio25;")]
#![cfg_attr(esp32s2, doc = "let dac1_pin = io.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();

View File

@ -18,17 +18,15 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::dma_buffers;
//! # use esp_hal::gpio::Io;
//! # use esp_hal::spi::{master::{Config, Spi}, SpiMode};
//! # use esp_hal::dma::{Dma, DmaPriority};
//! let dma = Dma::new(peripherals.DMA);
#![cfg_attr(any(esp32, esp32s2), doc = "let dma_channel = dma.spi2channel;")]
#![cfg_attr(not(any(esp32, esp32s2)), doc = "let dma_channel = dma.channel0;")]
//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! let sclk = io.pins.gpio0;
//! let miso = io.pins.gpio2;
//! let mosi = io.pins.gpio4;
//! let cs = io.pins.gpio5;
//! let sclk = peripherals.GPIO0;
//! let miso = peripherals.GPIO2;
//! let mosi = peripherals.GPIO4;
//! let cs = peripherals.GPIO5;
//!
//! let mut spi = Spi::new_with_config(
//! peripherals.SPI2,

View File

@ -23,15 +23,13 @@
//! ## Examples
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::gpio::Io;
//! # use esp_hal::gpio::etm::{Channels, InputConfig, OutputConfig};
//! # use esp_hal::etm::Etm;
//! # use esp_hal::gpio::Pull;
//! # use esp_hal::gpio::Level;
//!
//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! let mut led = io.pins.gpio1;
//! let button = io.pins.gpio9;
//! let mut led = peripherals.GPIO1;
//! let button = peripherals.GPIO9;
//!
//! // setup ETM
//! let gpio_ext = Channels::new(peripherals.GPIO_SD);

View File

@ -25,7 +25,6 @@
//! ### Toggle an LED When a Button is Pressed
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::gpio::Io;
//! # use esp_hal::gpio::etm::Channels;
//! # use esp_hal::etm::Etm;
//! # use esp_hal::gpio::etm::InputConfig;
@ -33,9 +32,8 @@
//! # use esp_hal::gpio::Pull;
//! # use esp_hal::gpio::Level;
//! #
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let mut led = io.pins.gpio1;
//! # let button = io.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(

View File

@ -15,14 +15,15 @@
//! chip from Deep-sleep.
//!
//! # Example
//!
//! ## Configure a LP Pin as Output
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! use esp_hal::gpio::Io;
//! use esp_hal::gpio::lp_io::LowPowerOutput;
//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! // configure GPIO 1 as LP output pin
//! let lp_pin: LowPowerOutput<'_, 1> = LowPowerOutput::new(io.pins.gpio1);
//! let lp_pin: LowPowerOutput<'_, 1> =
//! LowPowerOutput::new(peripherals.GPIO1);
//! # }
//! ```

View File

@ -18,9 +18,10 @@
//! GPIO interrupts. For more information, see the
//! [`Io::set_interrupt_handler`].
//!
//! The pins are accessible via [`Io::pins`]. These pins can then be passed to
//! peripherals (such as SPI, UART, I2C, etc.), to pin drivers or can be
//! [`GpioPin::split`] into peripheral signals.
//! The pins are accessible via the [`crate::Peripherals`] struct returned by
//! [`crate::init`]. These pins can then be passed to peripherals (such as
//! SPI, UART, I2C, etc.), to pin drivers or can be [`GpioPin::split`] into
//! peripheral signals.
//!
//! Each pin is a different type initially. Internally, `esp-hal` will often
//! erase their types automatically, but they can also be converted into
@ -52,8 +53,7 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::gpio::{Io, Level, Output};
//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! let mut led = Output::new(io.pins.gpio5, Level::High);
//! let mut led = Output::new(peripherals.GPIO5, Level::High);
//! # }
//! ```
//!
@ -71,11 +71,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,
@ -716,6 +723,9 @@ impl Bank1GpioRegisterAccess {
/// GPIO pin
pub struct GpioPin<const GPIONUM: u8>;
/// Type-erased GPIO pin
pub struct AnyPin(pub(crate) AnyPinInner);
impl<const GPIONUM: u8> GpioPin<GPIONUM>
where
Self: Pin,
@ -813,17 +823,12 @@ pub(crate) fn bind_default_interrupt_handler() {
/// General Purpose Input/Output driver
pub struct Io {
_io_mux: IO_MUX,
/// The pins available on this chip
pub pins: Pins,
}
impl Io {
/// Initialize the I/O driver.
pub fn new(_gpio: GPIO, _io_mux: IO_MUX) -> Self {
Io {
_io_mux,
pins: unsafe { Pins::steal() },
}
pub fn new(_io_mux: IO_MUX) -> Self {
Io { _io_mux }
}
/// Set the interrupt priority for GPIO interrupts.
@ -911,20 +916,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();
@ -956,91 +961,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<GpioPin<$gpionum>> 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 {
$(
[<Gpio $gpionum >](GpioPin<$gpionum>),
[<Gpio $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::[<Gpio $gpionum >](_) => {
Self(AnyPinInner::[< Gpio $gpionum >](unsafe { GpioPin::steal() }))
Self(AnyPinInner::[< Gpio $gpionum >](unsafe { $crate::gpio::GpioPin::steal() }))
})+
}
}
@ -1049,7 +1033,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 {
@ -1066,7 +1049,6 @@ macro_rules! gpio {
}
#[doc(hidden)]
#[macro_export]
macro_rules! handle_gpio_input {
($this:expr, $inner:ident, $code:tt) => {
match $this {
@ -1083,7 +1065,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 {
@ -1100,7 +1081,6 @@ macro_rules! gpio {
}
#[doc(hidden)]
#[macro_export]
macro_rules! handle_rtcio_with_resistors {
($this:expr, $inner:ident, $code:tt) => {
match $this {

View File

@ -23,10 +23,8 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::gpio::rtc_io::LowPowerOutput;
//! # use esp_hal::gpio::Io;
//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! // configure GPIO 1 as ULP output pin
//! let lp_pin = LowPowerOutput::<'static, 1>::new(io.pins.gpio1);
//! let lp_pin = LowPowerOutput::<'static, 1>::new(peripherals.GPIO1);
//! # }
//! ```

View File

@ -19,8 +19,6 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::i2c::master::{Config, I2c};
//! # use esp_hal::gpio::Io;
//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//!
//! // Create a new peripheral object with the described wiring
//! // and standard I2C clock speed.
@ -28,8 +26,8 @@
//! peripherals.I2C0,
//! Config::default(),
//! )
//! .with_sda(io.pins.gpio1)
//! .with_scl(io.pins.gpio2);
//! .with_sda(peripherals.GPIO1)
//! .with_scl(peripherals.GPIO2);
//!
//! loop {
//! let mut data = [0u8; 22];

View File

@ -30,10 +30,8 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::i2s::master::{I2s, Standard, DataFormat};
//! # use esp_hal::gpio::Io;
//! # use esp_hal::dma_buffers;
//! # use esp_hal::dma::{Dma, DmaPriority};
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! let dma = Dma::new(peripherals.DMA);
#![cfg_attr(any(esp32, esp32s2), doc = "let dma_channel = dma.i2s0channel;")]
#![cfg_attr(not(any(esp32, esp32s2)), doc = "let dma_channel = dma.channel0;")]
@ -52,11 +50,11 @@
//! rx_descriptors,
//! tx_descriptors,
//! );
#![cfg_attr(not(esp32), doc = "let i2s = i2s.with_mclk(io.pins.gpio0);")]
#![cfg_attr(not(esp32), doc = "let i2s = i2s.with_mclk(peripherals.GPIO0);")]
//! let mut i2s_rx = i2s.i2s_rx
//! .with_bclk(io.pins.gpio1)
//! .with_ws(io.pins.gpio2)
//! .with_din(io.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();

View File

@ -16,12 +16,10 @@
//! master mode.
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::gpio::Io;
//! # use esp_hal::lcd_cam::{cam::{Camera, RxEightBits}, LcdCam};
//! # use fugit::RateExtU32;
//! # use esp_hal::dma_rx_stream_buffer;
//! # use esp_hal::dma::{Dma, DmaPriority};
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//!
//! # let dma = Dma::new(peripherals.DMA);
//! # let channel = dma.channel0;
@ -33,19 +31,19 @@
//! # DmaPriority::Priority0,
//! # );
//!
//! let mclk_pin = io.pins.gpio15;
//! let vsync_pin = io.pins.gpio6;
//! let href_pin = io.pins.gpio7;
//! let pclk_pin = io.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(
//! io.pins.gpio11,
//! io.pins.gpio9,
//! io.pins.gpio8,
//! io.pins.gpio10,
//! io.pins.gpio12,
//! io.pins.gpio18,
//! io.pins.gpio17,
//! io.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);

View File

@ -15,11 +15,9 @@
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::gpio::Io;
//! # use esp_hal::lcd_cam::{LcdCam, lcd::i8080::{Config, I8080, TxEightBits}};
//! # use esp_hal::dma_tx_buffer;
//! # use esp_hal::dma::{Dma, DmaPriority, DmaTxBuf};
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//!
//! # let dma = Dma::new(peripherals.DMA);
//! # let channel = dma.channel0;
@ -32,14 +30,14 @@
//! # );
//!
//! let tx_pins = TxEightBits::new(
//! io.pins.gpio9,
//! io.pins.gpio46,
//! io.pins.gpio3,
//! io.pins.gpio8,
//! io.pins.gpio18,
//! io.pins.gpio17,
//! io.pins.gpio16,
//! io.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);
//!
@ -50,7 +48,7 @@
//! 20.MHz(),
//! Config::default(),
//! )
//! .with_ctrl_pins(io.pins.gpio0, io.pins.gpio47);
//! .with_ctrl_pins(peripherals.GPIO0, peripherals.GPIO47);
//!
//! dma_buf.fill(&[0x55]);
//! let transfer = i8080.send(0x3Au8, 0, dma_buf).unwrap(); // RGB565

View File

@ -29,9 +29,7 @@
//! # use esp_hal::ledc::timer;
//! # use esp_hal::ledc::LowSpeed;
//! # use esp_hal::ledc::channel;
//! # use esp_hal::gpio::Io;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let led = io.pins.gpio0;
//! # let led = peripherals.GPIO0;
//!
//! let mut ledc = Ledc::new(peripherals.LEDC);
//! ledc.set_global_slow_clock(LSGlobalClkSource::APBClk);

View File

@ -81,8 +81,7 @@
//! });
//!
//! // Set GPIO0 as an output, and set its state high initially.
//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! let mut led = Output::new(io.pins.gpio0, Level::High);
//! let mut led = Output::new(peripherals.GPIO0, Level::High);
//!
//! let delay = Delay::new();
//!

View File

@ -52,10 +52,7 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::mcpwm::{operator::{DeadTimeCfg, PWMStream, PwmPinConfig}, timer::PwmWorkingMode, McPwm, PeripheralClockConfig};
//! # use esp_hal::gpio::Io;
//!
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let pin = io.pins.gpio0;
//! # let pin = peripherals.GPIO0;
//!
//! // initialize peripheral
#![cfg_attr(

View File

@ -479,8 +479,6 @@ impl<PWM: PwmPeripheral, const OP: u8, const IS_A: bool> embedded_hal::pwm::SetD
/// # use esp_hal::{mcpwm, prelude::*};
/// # use esp_hal::mcpwm::{McPwm, PeripheralClockConfig};
/// # use esp_hal::mcpwm::operator::{DeadTimeCfg, PwmPinConfig, PWMStream};
/// # use esp_hal::gpio::Io;
/// # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
/// // active high complementary using PWMA input
/// let bridge_active = DeadTimeCfg::new_ahc();
/// // use PWMB as input for both outputs
@ -497,9 +495,9 @@ impl<PWM: PwmPeripheral, const OP: u8, const IS_A: bool> embedded_hal::pwm::SetD
/// let mut mcpwm = McPwm::new(peripherals.MCPWM0, clock_cfg);
///
/// let mut pins = mcpwm.operator0.with_linked_pins(
/// io.pins.gpio0,
/// peripherals.GPIO0,
/// PwmPinConfig::UP_DOWN_ACTIVE_HIGH, // use PWMA as our main input
/// io.pins.gpio1,
/// peripherals.GPIO1,
/// PwmPinConfig::EMPTY, // keep PWMB "low"
/// bridge_off,
/// );

View File

@ -121,14 +121,14 @@ impl<T> 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 {
(
peripherals: [
$(
$name:ident <= $from_pac:tt $(($($interrupt:ident),*))?
), *$(,)?
],
pins: [
$( ( $pin:literal, $($pin_tokens:tt)* ) )*
]
) => {
/// Contains the generated peripherals which implement [`Peripheral`]
@ -235,13 +240,25 @@ mod peripheral_macros {
)*
}
pub(crate) mod gpio {
$crate::gpio! {
$( ($pin, $($pin_tokens)* ) )*
}
}
paste::paste! {
/// 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.
#[doc = concat!("The ", stringify!($name), " peripheral.")]
pub $name: peripherals::$name,
)*
$(
#[doc = concat!("GPIO", stringify!($pin))]
pub [<GPIO $pin>]: $crate::gpio::GpioPin<$pin>,
)*
}
impl Peripherals {
@ -271,6 +288,11 @@ mod peripheral_macros {
$(
$name: peripherals::$name::steal(),
)*
$(
[<GPIO $pin>]: $crate::gpio::GpioPin::<$pin>::steal(),
)*
}
}
}
}
@ -294,8 +316,7 @@ mod peripheral_macros {
}
)*
)*
}
};
}
#[doc(hidden)]

View File

@ -54,16 +54,14 @@
//! # use esp_hal::peripherals::Peripherals;
//! # use esp_hal::rmt::TxChannelConfig;
//! # use esp_hal::rmt::Rmt;
//! # use esp_hal::gpio::Io;
//! # use crate::esp_hal::rmt::TxChannelCreator;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
#![cfg_attr(esp32h2, doc = "let freq = 32.MHz();")]
#![cfg_attr(not(esp32h2), doc = "let freq = 80.MHz();")]
//! let rmt = Rmt::new(peripherals.RMT, freq).unwrap();
//! let mut channel = rmt
//! .channel0
//! .configure(
//! io.pins.gpio1,
//! peripherals.GPIO1,
//! TxChannelConfig {
//! clk_divider: 1,
//! idle_output_level: false,

View File

@ -138,9 +138,7 @@ impl rand_core::RngCore for Rng {
/// # use esp_hal::peripherals::Peripherals;
/// # use esp_hal::peripherals::ADC1;
/// # use esp_hal::analog::adc::{AdcConfig, Attenuation, Adc};
/// # use esp_hal::gpio::Io;
///
/// let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
/// let mut buf = [0u8; 16];
///
/// // ADC is not available from now
@ -149,13 +147,15 @@ 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 = io.pins.gpio32;")]
#[cfg_attr(not(esp32), doc = "let analog_pin = io.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,
/// Attenuation::Attenuation11dB); let mut adc1 =
/// Adc::<ADC1>::new(peripherals.ADC1, adc1_config); let pin_value: u16 =
/// nb::block!(adc1.read_oneshot(&mut adc1_pin)).unwrap();
/// let mut adc1_pin = adc1_config.enable_pin(
/// analog_pin,
/// Attenuation::Attenuation11dB
/// );
/// let mut adc1 = Adc::<ADC1>::new(peripherals.ADC1, adc1_config);
/// let pin_value: u16 = nb::block!(adc1.read_oneshot(&mut adc1_pin)).unwrap();
/// rng.read(&mut buf);
/// true_rand = rng.random();
/// let pin_value: u16 = nb::block!(adc1.read_oneshot(&mut adc1_pin)).unwrap();

View File

@ -32,11 +32,9 @@
#![doc = crate::before_snippet!()]
//! # use esp_hal::rom::md5;
//! # use esp_hal::uart::Uart;
//! # use esp_hal::gpio::Io;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let mut uart0 = Uart::new(peripherals.UART0, io.pins.gpio1, io.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,11 +46,9 @@
#![doc = crate::before_snippet!()]
//! # use esp_hal::rom::md5;
//! # use esp_hal::uart::Uart;
//! # use esp_hal::gpio::Io;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let mut uart0 = Uart::new(peripherals.UART0, io.pins.gpio1, io.pins.gpio2).unwrap();
//! # let mut uart0 = Uart::new(peripherals.UART0, peripherals.GPIO1, peripherals.GPIO2).unwrap();
//! # let data0 = "Dummy";
//! # let data1 = "Dummy";
//! #

View File

@ -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.

View File

@ -24,12 +24,10 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::efuse::Efuse;
//! # use esp_hal::gpio::Io;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let mut serial_tx = Uart::new(peripherals.UART0, io.pins.gpio4, io.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,

View File

@ -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 )

View File

@ -20,6 +20,7 @@ pub(crate) use self::peripherals::*;
// peripheral (no `PSRAM`, `RADIO`, etc. peripheral in the PACs), so we're
// creating "virtual peripherals" for them.
crate::peripherals! {
peripherals: [
ADC1 <= virtual,
ADC2 <= virtual,
AES <= AES,
@ -33,7 +34,6 @@ crate::peripherals! {
EFUSE <= EFUSE,
FLASH_ENCRYPTION <= FLASH_ENCRYPTION,
FRC_TIMER <= FRC_TIMER,
GPIO <= GPIO (GPIO,GPIO_NMI),
GPIO_SD <= GPIO_SD,
HINF <= HINF,
I2C0 <= I2C0,
@ -74,4 +74,43 @@ crate::peripherals! {
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])
]
}

View File

@ -21,12 +21,10 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::efuse::Efuse;
//! # use esp_hal::gpio::Io;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let mut serial_tx = Uart::new(peripherals.UART0, io.pins.gpio4, io.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,

View File

@ -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

View File

@ -20,6 +20,7 @@ pub(crate) use self::peripherals::*;
// peripheral (no `PSRAM`, `RADIO`, etc. peripheral in the PACs), so we're
// creating "virtual peripherals" for them.
crate::peripherals! {
peripherals: [
ADC1 <= virtual,
APB_CTRL <= APB_CTRL,
ASSIST_DEBUG <= ASSIST_DEBUG,
@ -28,7 +29,6 @@ crate::peripherals! {
ECC <= ECC,
EFUSE <= EFUSE,
EXTMEM <= EXTMEM,
GPIO <= GPIO (GPIO,GPIO_NMI),
I2C0 <= I2C0,
INTERRUPT_CORE0 <= INTERRUPT_CORE0,
IO_MUX <= IO_MUX,
@ -56,4 +56,21 @@ crate::peripherals! {
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) ())
]
}

View File

@ -22,12 +22,10 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::efuse::Efuse;
//! # use esp_hal::gpio::Io;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let mut serial_tx = Uart::new(peripherals.UART0, io.pins.gpio4, io.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,

View File

@ -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

View File

@ -20,6 +20,7 @@ pub(crate) use self::peripherals::*;
// peripheral (no `PSRAM`, `RADIO`, etc. peripheral in the PACs), so we're
// creating "virtual peripherals" for them.
crate::peripherals! {
peripherals: [
ADC1 <= virtual,
ADC2 <= virtual,
AES <= AES,
@ -30,7 +31,6 @@ crate::peripherals! {
DS <= DS,
EFUSE <= EFUSE,
EXTMEM <= EXTMEM,
GPIO <= GPIO (GPIO,GPIO_NMI),
GPIO_SD <= GPIO_SD,
HMAC <= HMAC,
I2C0 <= I2C0,
@ -61,4 +61,29 @@ crate::peripherals! {
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))
]
}

View File

@ -22,12 +22,10 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::efuse::Efuse;
//! # use esp_hal::gpio::Io;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let mut serial_tx = Uart::new(peripherals.UART0, io.pins.gpio4, io.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,

View File

@ -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

View File

@ -20,6 +20,7 @@ pub(crate) use self::peripherals::*;
// peripheral (no `PSRAM`, `RADIO`, etc. peripheral in the PACs), so we're
// creating "virtual peripherals" for them.
crate::peripherals! {
peripherals: [
ADC1 <= virtual,
AES <= AES,
ASSIST_DEBUG <= ASSIST_DEBUG,
@ -30,7 +31,6 @@ crate::peripherals! {
ECC <= ECC,
EFUSE <= EFUSE,
EXTMEM <= EXTMEM,
GPIO <= GPIO (GPIO,GPIO_NMI),
GPIO_SD <= GPIO_SD,
HINF <= HINF,
HMAC <= HMAC,
@ -97,4 +97,38 @@ crate::peripherals! {
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))
]
}

View File

@ -22,12 +22,10 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::efuse::Efuse;
//! # use esp_hal::gpio::Io;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let mut serial_tx = Uart::new(peripherals.UART0, io.pins.gpio4, io.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,

View File

@ -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,

View File

@ -20,6 +20,7 @@ pub(crate) use self::peripherals::*;
// peripheral (no `PSRAM`, `RADIO`, etc. peripheral in the PACs), so we're
// creating "virtual peripherals" for them.
crate::peripherals! {
peripherals: [
ADC1 <= virtual,
AES <= AES,
ASSIST_DEBUG <= ASSIST_DEBUG,
@ -28,7 +29,6 @@ crate::peripherals! {
DS <= DS,
ECC <= ECC,
EFUSE <= EFUSE,
GPIO <= GPIO (GPIO,GPIO_NMI),
GPIO_SD <= GPIO_SD,
HMAC <= HMAC,
HP_APM <= HP_APM,
@ -87,4 +87,35 @@ crate::peripherals! {
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))
]
}

View File

@ -24,12 +24,10 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::efuse::Efuse;
//! # use esp_hal::gpio::Io;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let mut serial_tx = Uart::new(peripherals.UART0, io.pins.gpio4, io.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,

View File

@ -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 )

View File

@ -20,6 +20,7 @@ pub(crate) use self::peripherals::*;
// peripheral (no `PSRAM`, `RADIO`, etc. peripheral in the PACs), so we're
// creating "virtual peripherals" for them.
crate::peripherals! {
peripherals: [
ADC1 <= virtual,
ADC2 <= virtual,
AES <= AES,
@ -30,7 +31,6 @@ crate::peripherals! {
DS <= DS,
EFUSE <= EFUSE,
EXTMEM <= EXTMEM,
GPIO <= GPIO (GPIO,GPIO_NMI),
GPIO_SD <= GPIO_SD,
HMAC <= HMAC,
I2C0 <= I2C0,
@ -69,4 +69,51 @@ crate::peripherals! {
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])
]
}

View File

@ -22,12 +22,10 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::efuse::Efuse;
//! # use esp_hal::gpio::Io;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let mut serial_tx = Uart::new(peripherals.UART0, io.pins.gpio4, io.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,

View File

@ -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 )

View File

@ -20,6 +20,7 @@ pub(crate) use self::peripherals::*;
// peripheral (no `PSRAM`, `RADIO`, etc. peripheral in the PACs), so we're
// creating "virtual peripherals" for them.
crate::peripherals! {
peripherals: [
ADC1 <= virtual,
ADC2 <= virtual,
AES <= AES,
@ -31,7 +32,6 @@ crate::peripherals! {
DS <= DS,
EFUSE <= EFUSE,
EXTMEM <= EXTMEM,
GPIO <= GPIO (GPIO,GPIO_NMI),
GPIO_SD <= GPIO_SD,
HMAC <= HMAC,
I2C0 <= I2C0,
@ -79,4 +79,52 @@ crate::peripherals! {
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])
]
}

View File

@ -40,12 +40,10 @@
#![doc = crate::before_snippet!()]
//! # use esp_hal::spi::SpiMode;
//! # use esp_hal::spi::master::{Config, Spi};
//! # use esp_hal::gpio::Io;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! let sclk = io.pins.gpio0;
//! let miso = io.pins.gpio2;
//! let mosi = io.pins.gpio1;
//! let cs = io.pins.gpio5;
//! let sclk = peripherals.GPIO0;
//! let miso = peripherals.GPIO2;
//! let mosi = peripherals.GPIO1;
//! let cs = peripherals.GPIO5;
//!
//! let mut spi = Spi::new_with_config(
//! peripherals.SPI2,

View File

@ -20,15 +20,13 @@
//! # use esp_hal::spi::SpiMode;
//! # use esp_hal::spi::slave::Spi;
//! # use esp_hal::dma::Dma;
//! # use esp_hal::gpio::Io;
//! 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 io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! let sclk = io.pins.gpio0;
//! let miso = io.pins.gpio1;
//! let mosi = io.pins.gpio2;
//! let cs = io.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);

View File

@ -10,9 +10,7 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::touch::{Touch, TouchPad};
//! # use esp_hal::gpio::Io;
//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! let touch_pin0 = io.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

View File

@ -32,14 +32,12 @@
//! # use esp_hal::twai::TwaiConfiguration;
//! # use esp_hal::twai::BaudRate;
//! # use esp_hal::twai::TwaiMode;
//! # use esp_hal::gpio::Io;
//! # use embedded_can::Frame;
//! # use nb::block;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! // Use GPIO pins 2 and 3 to connect to the respective pins on the TWAI
//! // transceiver.
//! let can_rx_pin = io.pins.gpio3;
//! let can_tx_pin = io.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;
@ -86,14 +84,12 @@
//! # use esp_hal::twai::EspTwaiFrame;
//! # use esp_hal::twai::StandardId;
//! # use esp_hal::twai::TwaiMode;
//! # use esp_hal::gpio::Io;
//! # use embedded_can::Frame;
//! # use nb::block;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! // Use GPIO pins 2 and 3 to connect to the respective pins on the TWAI
//! // transceiver.
//! let can_rx_pin = io.pins.gpio3;
//! let can_tx_pin = io.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;

View File

@ -23,14 +23,11 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::uart::Uart;
//! use esp_hal::gpio::Io;
//!
//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//!
//! let mut uart1 = Uart::new(
//! peripherals.UART1,
//! io.pins.gpio1,
//! io.pins.gpio2,
//! peripherals.GPIO1,
//! peripherals.GPIO2,
//! ).unwrap();
//! # }
//! ```
@ -56,13 +53,11 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::uart::{Config, Uart};
//! # use esp_hal::gpio::Io;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let mut uart1 = Uart::new_with_config(
//! # peripherals.UART1,
//! # Config::default(),
//! # io.pins.gpio1,
//! # io.pins.gpio2,
//! # peripherals.GPIO1,
//! # peripherals.GPIO2,
//! # ).unwrap();
//! // Write bytes out over the UART:
//! uart1.write_bytes(b"Hello, world!").expect("write error!");
@ -73,13 +68,11 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::uart::{Config, Uart};
//! # use esp_hal::gpio::Io;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let mut uart1 = Uart::new_with_config(
//! # peripherals.UART1,
//! # Config::default(),
//! # io.pins.gpio1,
//! # io.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();
@ -94,12 +87,9 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::uart::Uart;
//! use esp_hal::gpio::Io;
//!
//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//!
//! let (rx, _) = io.pins.gpio2.split();
//! let (_, tx) = io.pins.gpio1.split();
//! let (rx, _) = peripherals.GPIO2.split();
//! let (_, tx) = peripherals.GPIO1.split();
//! let mut uart1 = Uart::new(
//! peripherals.UART1,
//! rx.inverted(),
@ -112,12 +102,9 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::uart::{UartTx, UartRx};
//! use esp_hal::gpio::Io;
//!
//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//!
//! let tx = UartTx::new(peripherals.UART0, io.pins.gpio1).unwrap();
//! let rx = UartRx::new(peripherals.UART1, io.pins.gpio2).unwrap();
//! let tx = UartTx::new(peripherals.UART0, peripherals.GPIO1).unwrap();
//! let rx = UartRx::new(peripherals.UART1, peripherals.GPIO2).unwrap();
//! # }
//! ```
//!

View File

@ -20,7 +20,6 @@ use esp_backtrace as _;
use esp_hal::{
analog::adc::{Adc, AdcConfig, Attenuation},
delay::Delay,
gpio::Io,
prelude::*,
};
use esp_println::println;
@ -29,14 +28,13 @@ use esp_println::println;
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
cfg_if::cfg_if! {
if #[cfg(feature = "esp32")] {
let analog_pin = io.pins.gpio32;
let analog_pin = peripherals.GPIO32;
} else if #[cfg(any(feature = "esp32s2", feature = "esp32s3"))] {
let analog_pin = io.pins.gpio3;
let analog_pin = peripherals.GPIO3;
} else {
let analog_pin = io.pins.gpio2;
let analog_pin = peripherals.GPIO2;
}
}

View File

@ -16,7 +16,6 @@ use esp_backtrace as _;
use esp_hal::{
analog::adc::{Adc, AdcConfig, Attenuation},
delay::Delay,
gpio::Io,
prelude::*,
};
use esp_println::println;
@ -25,12 +24,11 @@ use esp_println::println;
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
cfg_if::cfg_if! {
if #[cfg(feature = "esp32s3")] {
let analog_pin = io.pins.gpio3;
let analog_pin = peripherals.GPIO3;
} else {
let analog_pin = io.pins.gpio2;
let analog_pin = peripherals.GPIO2;
}
}

View File

@ -13,7 +13,7 @@
#![no_main]
use esp_backtrace as _;
use esp_hal::{delay::Delay, gpio::Io, prelude::*, uart::Uart};
use esp_hal::{delay::Delay, prelude::*, uart::Uart};
use esp_println::println;
use nb::block;
@ -21,9 +21,7 @@ use nb::block;
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let mut serial1 = Uart::new(peripherals.UART1, io.pins.gpio4, io.pins.gpio5).unwrap();
let mut serial1 = Uart::new(peripherals.UART1, peripherals.GPIO4, peripherals.GPIO5).unwrap();
let delay = Delay::new();

View File

@ -11,7 +11,7 @@
use esp_backtrace as _;
use esp_hal::{
delay::Delay,
gpio::{Io, Level, Output},
gpio::{Level, Output},
prelude::*,
};
@ -20,8 +20,8 @@ fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
// Set GPIO0 as an output, and set its state high initially.
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let mut led = Output::new(io.pins.gpio0, Level::High);
let mut led = Output::new(peripherals.GPIO0, Level::High);
let delay = Delay::new();

View File

@ -14,7 +14,7 @@
use esp_backtrace as _;
use esp_hal::{
delay::Delay,
gpio::{Input, Io, Level, Output, Pin, Pull},
gpio::{Input, Level, Output, Pin, Pull},
prelude::*,
};
@ -22,18 +22,16 @@ use esp_hal::{
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
// Set LED GPIOs as an output:
let led1 = Output::new(io.pins.gpio2.degrade(), Level::Low);
let led2 = Output::new(io.pins.gpio4.degrade(), Level::Low);
let led3 = Output::new(io.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 = io.pins.gpio0.degrade();
let button = peripherals.GPIO0.degrade();
#[cfg(not(any(feature = "esp32", feature = "esp32s2", feature = "esp32s3")))]
let button = io.pins.gpio9.degrade();
let button = peripherals.GPIO9.degrade();
let button = Input::new(button, Pull::Up);

View File

@ -19,21 +19,19 @@
#![no_main]
use esp_backtrace as _;
use esp_hal::{analog::dac::Dac, delay::Delay, gpio::Io, prelude::*};
use esp_hal::{analog::dac::Dac, delay::Delay, prelude::*};
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
cfg_if::cfg_if! {
if #[cfg(feature = "esp32")] {
let dac1_pin = io.pins.gpio25;
let dac2_pin = io.pins.gpio26;
let dac1_pin = peripherals.GPIO25;
let dac2_pin = peripherals.GPIO26;
} else if #[cfg(feature = "esp32s2")] {
let dac1_pin = io.pins.gpio17;
let dac2_pin = io.pins.gpio18;
let dac1_pin = peripherals.GPIO17;
let dac2_pin = peripherals.GPIO18;
}
}

View File

@ -20,7 +20,6 @@ use embassy_executor::Spawner;
use embassy_time::{Duration, Timer};
use esp_backtrace as _;
use esp_hal::{
gpio::Io,
i2c::master::{Config, I2c},
prelude::*,
timer::timg::TimerGroup,
@ -34,15 +33,13 @@ async fn main(_spawner: Spawner) {
let timg0 = TimerGroup::new(peripherals.TIMG0);
esp_hal_embassy::init(timg0.timer0);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let i2c0 = I2c::new(peripherals.I2C0, {
let mut config = Config::default();
config.frequency = 400.kHz();
config
})
.with_sda(io.pins.gpio4)
.with_scl(io.pins.gpio5)
.with_sda(peripherals.GPIO4)
.with_scl(peripherals.GPIO5)
.into_async();
let mut lis3dh = Lis3dh::new_i2c(i2c0, SlaveAddr::Alternate).await.unwrap();

View File

@ -21,7 +21,6 @@ use embassy_executor::Spawner;
use embassy_time::{Duration, Timer};
use esp_backtrace as _;
use esp_hal::{
gpio::Io,
i2c::master::{Config, I2c},
prelude::*,
timer::timg::TimerGroup,
@ -34,15 +33,13 @@ async fn main(_spawner: Spawner) {
let timg0 = TimerGroup::new(peripherals.TIMG0);
esp_hal_embassy::init(timg0.timer0);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let mut i2c = I2c::new(peripherals.I2C0, {
let mut config = Config::default();
config.frequency = 400.kHz();
config
})
.with_sda(io.pins.gpio4)
.with_scl(io.pins.gpio5)
.with_sda(peripherals.GPIO4)
.with_scl(peripherals.GPIO5)
.into_async();
loop {

View File

@ -20,7 +20,6 @@ use esp_backtrace as _;
use esp_hal::{
dma::{Dma, DmaPriority, DmaTxBuf},
dma_buffers,
gpio::Io,
i2s::parallel::{I2sParallel, TxEightBits},
prelude::*,
timer::timg::TimerGroup,
@ -35,7 +34,6 @@ async fn main(_spawner: Spawner) {
info!("Starting!");
let peripherals = esp_hal::init(esp_hal::Config::default());
let dma = Dma::new(peripherals.DMA);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let timg0 = TimerGroup::new(peripherals.TIMG0);
@ -44,17 +42,17 @@ async fn main(_spawner: Spawner) {
let dma_channel = dma.i2s1channel;
let i2s = peripherals.I2S1;
let clock = io.pins.gpio25;
let clock = peripherals.GPIO25;
let pins = TxEightBits::new(
io.pins.gpio16,
io.pins.gpio4,
io.pins.gpio17,
io.pins.gpio18,
io.pins.gpio5,
io.pins.gpio19,
io.pins.gpio12,
io.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);

View File

@ -22,7 +22,6 @@ use esp_backtrace as _;
use esp_hal::{
dma::{Dma, DmaPriority},
dma_buffers,
gpio::Io,
i2s::master::{DataFormat, I2s, Standard},
prelude::*,
timer::timg::TimerGroup,
@ -37,8 +36,6 @@ async fn main(_spawner: Spawner) {
let timg0 = TimerGroup::new(peripherals.TIMG0);
esp_hal_embassy::init(timg0.timer0);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let dma = Dma::new(peripherals.DMA);
#[cfg(any(feature = "esp32", feature = "esp32s2"))]
let dma_channel = dma.i2s0channel;
@ -59,13 +56,13 @@ async fn main(_spawner: Spawner) {
.into_async();
#[cfg(not(feature = "esp32"))]
let i2s = i2s.with_mclk(io.pins.gpio0);
let i2s = i2s.with_mclk(peripherals.GPIO0);
let i2s_rx = i2s
.i2s_rx
.with_bclk(io.pins.gpio2)
.with_ws(io.pins.gpio4)
.with_din(io.pins.gpio5)
.with_bclk(peripherals.GPIO2)
.with_ws(peripherals.GPIO4)
.with_din(peripherals.GPIO5)
.build();
let buffer = rx_buffer;

View File

@ -36,7 +36,6 @@ use esp_backtrace as _;
use esp_hal::{
dma::{Dma, DmaPriority},
dma_buffers,
gpio::Io,
i2s::master::{DataFormat, I2s, Standard},
prelude::*,
timer::timg::TimerGroup,
@ -59,8 +58,6 @@ async fn main(_spawner: Spawner) {
let timg0 = TimerGroup::new(peripherals.TIMG0);
esp_hal_embassy::init(timg0.timer0);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let dma = Dma::new(peripherals.DMA);
#[cfg(any(feature = "esp32", feature = "esp32s2"))]
let dma_channel = dma.i2s0channel;
@ -82,9 +79,9 @@ async fn main(_spawner: Spawner) {
let i2s_tx = i2s
.i2s_tx
.with_bclk(io.pins.gpio2)
.with_ws(io.pins.gpio4)
.with_dout(io.pins.gpio5)
.with_bclk(peripherals.GPIO2)
.with_ws(peripherals.GPIO4)
.with_dout(peripherals.GPIO5)
.build();
let data =

View File

@ -21,7 +21,7 @@ use esp_backtrace as _;
use esp_hal::{
cpu_control::{CpuControl, Stack},
get_core,
gpio::{Io, Level, Output},
gpio::{Level, Output},
timer::{timg::TimerGroup, AnyTimer},
};
use esp_hal_embassy::Executor;
@ -53,8 +53,6 @@ async fn control_led(
async fn main(_spawner: Spawner) {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let timg0 = TimerGroup::new(peripherals.TIMG0);
let timer0: AnyTimer = timg0.timer0.into();
let timer1: AnyTimer = timg0.timer1.into();
@ -65,7 +63,7 @@ async fn main(_spawner: Spawner) {
static LED_CTRL: StaticCell<Signal<CriticalSectionRawMutex, bool>> = StaticCell::new();
let led_ctrl_signal = &*LED_CTRL.init(Signal::new());
let led = Output::new(io.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 || {

View File

@ -20,7 +20,7 @@ use esp_backtrace as _;
use esp_hal::{
cpu_control::{CpuControl, Stack},
get_core,
gpio::{Io, Level, Output},
gpio::{Level, Output},
interrupt::{software::SoftwareInterruptControl, Priority},
prelude::*,
timer::{timg::TimerGroup, AnyTimer},
@ -75,8 +75,6 @@ fn main() -> ! {
let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let timg0 = TimerGroup::new(peripherals.TIMG0);
let timer0: AnyTimer = timg0.timer0.into();
let timer1: AnyTimer = timg0.timer1.into();
@ -87,7 +85,7 @@ fn main() -> ! {
static LED_CTRL: StaticCell<Signal<CriticalSectionRawMutex, bool>> = StaticCell::new();
let led_ctrl_signal = &*LED_CTRL.init(Signal::new());
let led = Output::new(io.pins.gpio0, Level::Low);
let led = Output::new(peripherals.GPIO0, Level::Low);
static EXECUTOR_CORE_1: StaticCell<InterruptExecutor<1>> = StaticCell::new();
let executor_core1 = InterruptExecutor::new(sw_ints.software_interrupt1);

View File

@ -16,7 +16,6 @@ use esp_backtrace as _;
use esp_hal::{
dma::{Dma, DmaPriority},
dma_buffers,
gpio::Io,
parl_io::{no_clk_pin, BitPackOrder, ParlIoRxOnly, RxFourBits},
prelude::*,
timer::systimer::{SystemTimer, Target},
@ -31,14 +30,17 @@ async fn main(_spawner: Spawner) {
let systimer = SystemTimer::new(peripherals.SYSTIMER).split::<Target>();
esp_hal_embassy::init(systimer.alarm0);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let (rx_buffer, rx_descriptors, _, _) = dma_buffers!(32000, 0);
let dma = Dma::new(peripherals.DMA);
let dma_channel = dma.channel0;
let mut rx_pins = RxFourBits::new(io.pins.gpio1, io.pins.gpio2, io.pins.gpio3, io.pins.gpio4);
let mut rx_pins = RxFourBits::new(
peripherals.GPIO1,
peripherals.GPIO2,
peripherals.GPIO3,
peripherals.GPIO4,
);
let parl_io = ParlIoRxOnly::new(
peripherals.PARL_IO,

View File

@ -20,7 +20,6 @@ use esp_backtrace as _;
use esp_hal::{
dma::{Dma, DmaPriority},
dma_buffers,
gpio::Io,
parl_io::{
BitPackOrder,
ClkOutPin,
@ -42,16 +41,19 @@ async fn main(_spawner: Spawner) {
let systimer = SystemTimer::new(peripherals.SYSTIMER).split::<Target>();
esp_hal_embassy::init(systimer.alarm0);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let (_, _, tx_buffer, tx_descriptors) = dma_buffers!(0, 32000);
let dma = Dma::new(peripherals.DMA);
let dma_channel = dma.channel0;
let tx_pins = TxFourBits::new(io.pins.gpio1, io.pins.gpio2, io.pins.gpio3, io.pins.gpio4);
let tx_pins = TxFourBits::new(
peripherals.GPIO1,
peripherals.GPIO2,
peripherals.GPIO3,
peripherals.GPIO4,
);
let mut pin_conf = TxPinConfigWithValidPin::new(tx_pins, io.pins.gpio5);
let mut pin_conf = TxPinConfigWithValidPin::new(tx_pins, peripherals.GPIO5);
let parl_io = ParlIoTxOnly::new(
peripherals.PARL_IO,
@ -63,7 +65,7 @@ async fn main(_spawner: Spawner) {
)
.unwrap();
let mut clock_pin = ClkOutPin::new(io.pins.gpio8);
let mut clock_pin = ClkOutPin::new(peripherals.GPIO8);
let mut parl_io_tx = parl_io
.tx

View File

@ -13,7 +13,7 @@ use embassy_executor::Spawner;
use embassy_time::{Duration, Timer};
use esp_backtrace as _;
use esp_hal::{
gpio::{Io, Level, Output},
gpio::{Level, Output},
prelude::*,
rmt::{PulseCode, Rmt, RxChannelAsync, RxChannelConfig, RxChannelCreatorAsync},
timer::timg::TimerGroup,
@ -44,8 +44,6 @@ async fn main(spawner: Spawner) {
let timg0 = TimerGroup::new(peripherals.TIMG0);
esp_hal_embassy::init(timg0.timer0);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
cfg_if::cfg_if! {
if #[cfg(feature = "esp32h2")] {
let freq = 32.MHz();
@ -63,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(io.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(io.pins.gpio4, rx_config).unwrap();
let mut channel = rmt.channel7.configure(peripherals.GPIO4, rx_config).unwrap();
} else {
let mut channel = rmt.channel2.configure(io.pins.gpio4, rx_config).unwrap();
let mut channel = rmt.channel2.configure(peripherals.GPIO4, rx_config).unwrap();
}
}
spawner
.spawn(signal_task(Output::new(io.pins.gpio5, Level::Low)))
.spawn(signal_task(Output::new(peripherals.GPIO5, Level::Low)))
.unwrap();
let mut data = [PulseCode {

View File

@ -15,7 +15,6 @@ use embassy_executor::Spawner;
use embassy_time::{Duration, Timer};
use esp_backtrace as _;
use esp_hal::{
gpio::Io,
prelude::*,
rmt::{PulseCode, Rmt, TxChannelAsync, TxChannelConfig, TxChannelCreatorAsync},
timer::timg::TimerGroup,
@ -30,8 +29,6 @@ async fn main(_spawner: Spawner) {
let timg0 = TimerGroup::new(peripherals.TIMG0);
esp_hal_embassy::init(timg0.timer0);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
cfg_if::cfg_if! {
if #[cfg(feature = "esp32h2")] {
let freq = 32.MHz();
@ -45,7 +42,7 @@ async fn main(_spawner: Spawner) {
let mut channel = rmt
.channel0
.configure(
io.pins.gpio4,
peripherals.GPIO4,
TxChannelConfig {
clk_divider: 255,
..TxChannelConfig::default()

View File

@ -13,7 +13,6 @@ use embassy_executor::Spawner;
use embassy_sync::{blocking_mutex::raw::NoopRawMutex, signal::Signal};
use esp_backtrace as _;
use esp_hal::{
gpio::Io,
timer::timg::TimerGroup,
uart::{AtCmdConfig, Config, Uart, UartRx, UartTx},
Async,
@ -71,22 +70,20 @@ async fn main(spawner: Spawner) {
let timg0 = TimerGroup::new(peripherals.TIMG0);
esp_hal_embassy::init(timg0.timer0);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
// Default pins for Uart/Serial communication
cfg_if::cfg_if! {
if #[cfg(feature = "esp32")] {
let (tx_pin, rx_pin) = (io.pins.gpio1, io.pins.gpio3);
let (tx_pin, rx_pin) = (peripherals.GPIO1, peripherals.GPIO3);
} else if #[cfg(feature = "esp32c2")] {
let (tx_pin, rx_pin) = (io.pins.gpio20, io.pins.gpio19);
let (tx_pin, rx_pin) = (peripherals.GPIO20, peripherals.GPIO19);
} else if #[cfg(feature = "esp32c3")] {
let (tx_pin, rx_pin) = (io.pins.gpio21, io.pins.gpio20);
let (tx_pin, rx_pin) = (peripherals.GPIO21, peripherals.GPIO20);
} else if #[cfg(feature = "esp32c6")] {
let (tx_pin, rx_pin) = (io.pins.gpio16, io.pins.gpio17);
let (tx_pin, rx_pin) = (peripherals.GPIO16, peripherals.GPIO17);
} else if #[cfg(feature = "esp32h2")] {
let (tx_pin, rx_pin) = (io.pins.gpio24, io.pins.gpio23);
let (tx_pin, rx_pin) = (peripherals.GPIO24, peripherals.GPIO23);
} else if #[cfg(any(feature = "esp32s2", feature = "esp32s3"))] {
let (tx_pin, rx_pin) = (io.pins.gpio43, io.pins.gpio44);
let (tx_pin, rx_pin) = (peripherals.GPIO43, peripherals.GPIO44);
}
}

View File

@ -24,7 +24,6 @@ use esp_backtrace as _;
use esp_hal::{
dma::*,
dma_buffers,
gpio::Io,
prelude::*,
spi::{
master::{Config, Spi},
@ -41,11 +40,10 @@ async fn main(_spawner: Spawner) {
let timg0 = TimerGroup::new(peripherals.TIMG0);
esp_hal_embassy::init(timg0.timer0);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let sclk = io.pins.gpio0;
let miso = io.pins.gpio2;
let mosi = io.pins.gpio4;
let cs = io.pins.gpio5;
let sclk = peripherals.GPIO0;
let miso = peripherals.GPIO2;
let mosi = peripherals.GPIO4;
let cs = peripherals.GPIO5;
let dma = Dma::new(peripherals.DMA);

View File

@ -17,7 +17,6 @@ use embassy_futures::select::{select, Either};
use embassy_time::{Duration, Timer};
use esp_backtrace as _;
use esp_hal::{
gpio::Io,
rtc_cntl::Rtc,
timer::timg::TimerGroup,
touch::{Touch, TouchConfig, TouchPad},
@ -32,11 +31,10 @@ async fn main(_spawner: Spawner) {
let timg0 = TimerGroup::new(peripherals.TIMG0);
esp_hal_embassy::init(timg0.timer0);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let mut rtc = Rtc::new(peripherals.LPWR);
let touch_pin0 = io.pins.gpio2;
let touch_pin1 = io.pins.gpio4;
let touch_pin0 = peripherals.GPIO2;
let touch_pin1 = peripherals.GPIO4;
let touch_cfg = Some(TouchConfig {
measurement_duration: Some(0x2000),

View File

@ -35,7 +35,6 @@ use embassy_sync::{blocking_mutex::raw::NoopRawMutex, channel::Channel};
use embedded_can::{Frame, Id};
use esp_backtrace as _;
use esp_hal::{
gpio::Io,
timer::timg::TimerGroup,
twai::{self, EspTwaiFrame, StandardId, TwaiMode, TwaiRx, TwaiTx},
};
@ -92,13 +91,11 @@ async fn main(spawner: Spawner) {
let timg0 = TimerGroup::new(peripherals.TIMG0);
esp_hal_embassy::init(timg0.timer0);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
// Without an external transceiver, we only need a single line between the two MCUs.
let (rx_pin, tx_pin) = io.pins.gpio2.split();
let (rx_pin, tx_pin) = peripherals.GPIO2.split();
// Use these if you want to use an external transceiver:
// let tx_pin = io.pins.gpio2;
// let rx_pin = io.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;

View File

@ -21,7 +21,6 @@ use embassy_usb::{
};
use esp_backtrace as _;
use esp_hal::{
gpio::Io,
otg_fs::{
asynch::{Config, Driver},
Usb,
@ -37,9 +36,7 @@ async fn main(_spawner: Spawner) {
let timg0 = TimerGroup::new(peripherals.TIMG0);
esp_hal_embassy::init(timg0.timer0);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let usb = Usb::new(peripherals.USB0, io.pins.gpio20, io.pins.gpio19);
let usb = Usb::new(peripherals.USB0, peripherals.GPIO20, peripherals.GPIO19);
// Create the driver, from the HAL.
let mut ep_out_buffer = [0u8; 1024];

View File

@ -12,7 +12,7 @@ use embassy_executor::Spawner;
use embassy_time::{Duration, Timer};
use esp_backtrace as _;
use esp_hal::{
gpio::{Input, Io, Pull},
gpio::{Input, Pull},
timer::timg::TimerGroup,
};
@ -24,13 +24,11 @@ async fn main(_spawner: Spawner) {
let timg0 = TimerGroup::new(peripherals.TIMG0);
esp_hal_embassy::init(timg0.timer0);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
cfg_if::cfg_if! {
if #[cfg(any(feature = "esp32", feature = "esp32s2", feature = "esp32s3"))] {
let mut input = Input::new(io.pins.gpio0, Pull::Down);
let mut input = Input::new(peripherals.GPIO0, Pull::Down);
} else {
let mut input = Input::new(io.pins.gpio9, Pull::Down);
let mut input = Input::new(peripherals.GPIO9, Pull::Down);
}
}

View File

@ -13,7 +13,6 @@ use esp_hal::{
etm::Etm,
gpio::{
etm::{Channels, OutputConfig},
Io,
Level,
Pull,
},
@ -31,8 +30,7 @@ fn main() -> ! {
let mut alarm0 = syst_alarms.alarm0;
alarm0.set_period(1u32.secs());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let mut led = io.pins.gpio1;
let mut led = peripherals.GPIO1;
// setup ETM
let gpio_ext = Channels::new(peripherals.GPIO_SD);

View File

@ -13,7 +13,6 @@ use esp_hal::{
etm::Etm,
gpio::{
etm::{Channels, InputConfig, OutputConfig},
Io,
Level,
Output,
Pull,
@ -25,10 +24,8 @@ use esp_hal::{
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let mut led = Output::new(io.pins.gpio1, Level::Low);
let button = io.pins.gpio9;
let mut led = Output::new(peripherals.GPIO1, Level::Low);
let button = peripherals.GPIO9;
led.set_high();

View File

@ -30,15 +30,15 @@ fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
// Set GPIO2 as an output, and set its state high initially.
let mut io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let mut io = Io::new(peripherals.IO_MUX);
io.set_interrupt_handler(handler);
let mut led = Output::new(io.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 = io.pins.gpio0;
let button = peripherals.GPIO0;
} else {
let button = io.pins.gpio9;
let button = peripherals.GPIO9;
}
}

View File

@ -15,7 +15,7 @@
use core::fmt::Write;
use esp_backtrace as _;
use esp_hal::{delay::Delay, gpio::Io, prelude::*, uart::Uart};
use esp_hal::{delay::Delay, prelude::*, uart::Uart};
#[entry]
fn main() -> ! {
@ -23,22 +23,20 @@ fn main() -> ! {
let delay = Delay::new();
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
// Default pins for Uart/Serial communication
cfg_if::cfg_if! {
if #[cfg(feature = "esp32")] {
let (mut tx_pin, mut rx_pin) = (io.pins.gpio1, io.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) = (io.pins.gpio20, io.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) = (io.pins.gpio21, io.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) = (io.pins.gpio16, io.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) = (io.pins.gpio24, io.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) = (io.pins.gpio43, io.pins.gpio44);
let (mut tx_pin, mut rx_pin) = (peripherals.GPIO43, peripherals.GPIO44);
}
}

View File

@ -13,7 +13,6 @@
use esp_backtrace as _;
use esp_hal::{
gpio::Io,
i2c::master::{Config, I2c},
prelude::*,
};
@ -23,13 +22,11 @@ use esp_println::println;
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
// Create a new peripheral object with the described wiring and standard
// I2C clock speed:
let mut i2c = I2c::new(peripherals.I2C0, Config::default())
.with_sda(io.pins.gpio4)
.with_scl(io.pins.gpio5);
.with_sda(peripherals.GPIO4)
.with_scl(peripherals.GPIO5);
loop {
let mut data = [0u8; 22];

View File

@ -24,7 +24,6 @@ use embedded_graphics::{
use esp_backtrace as _;
use esp_hal::{
delay::Delay,
gpio::Io,
i2c::master::{Config, I2c},
prelude::*,
};
@ -35,13 +34,12 @@ fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let delay = Delay::new();
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
// Create a new peripheral object with the described wiring
// and standard I2C clock speed
let i2c = I2c::new(peripherals.I2C0, Config::default())
.with_sda(io.pins.gpio4)
.with_scl(io.pins.gpio5);
.with_sda(peripherals.GPIO4)
.with_scl(peripherals.GPIO5);
// Initialize display
let interface = I2CDisplayInterface::new(i2c);

View File

@ -18,7 +18,6 @@ use esp_hal::{
delay::Delay,
dma::{Dma, DmaPriority, DmaTxBuf},
dma_buffers,
gpio::Io,
i2s::parallel::{I2sParallel, TxEightBits},
prelude::*,
};
@ -32,23 +31,22 @@ fn main() -> ! {
info!("Starting!");
let peripherals = esp_hal::init(esp_hal::Config::default());
let dma = Dma::new(peripherals.DMA);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let delay = Delay::new();
let dma_channel = dma.i2s1channel;
let i2s = peripherals.I2S1;
let clock = io.pins.gpio25;
let clock = peripherals.GPIO25;
let pins = TxEightBits::new(
io.pins.gpio16,
io.pins.gpio4,
io.pins.gpio17,
io.pins.gpio18,
io.pins.gpio5,
io.pins.gpio19,
io.pins.gpio12,
io.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);

View File

@ -20,7 +20,6 @@ use esp_backtrace as _;
use esp_hal::{
dma::{Dma, DmaPriority},
dma_buffers,
gpio::Io,
i2s::master::{DataFormat, I2s, Standard},
prelude::*,
};
@ -30,8 +29,6 @@ use esp_println::println;
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let dma = Dma::new(peripherals.DMA);
#[cfg(any(feature = "esp32", feature = "esp32s2"))]
let dma_channel = dma.i2s0channel;
@ -55,13 +52,13 @@ fn main() -> ! {
);
#[cfg(not(feature = "esp32"))]
let i2s = i2s.with_mclk(io.pins.gpio0);
let i2s = i2s.with_mclk(peripherals.GPIO0);
let mut i2s_rx = i2s
.i2s_rx
.with_bclk(io.pins.gpio2)
.with_ws(io.pins.gpio4)
.with_din(io.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();

View File

@ -34,7 +34,6 @@ use esp_backtrace as _;
use esp_hal::{
dma::{Dma, DmaPriority},
dma_buffers,
gpio::Io,
i2s::master::{DataFormat, I2s, Standard},
prelude::*,
};
@ -51,8 +50,6 @@ const SINE: [i16; 64] = [
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let dma = Dma::new(peripherals.DMA);
#[cfg(any(feature = "esp32", feature = "esp32s2"))]
let dma_channel = dma.i2s0channel;
@ -73,9 +70,9 @@ fn main() -> ! {
let mut i2s_tx = i2s
.i2s_tx
.with_bclk(io.pins.gpio2)
.with_ws(io.pins.gpio4)
.with_dout(io.pins.gpio5)
.with_bclk(peripherals.GPIO2)
.with_ws(peripherals.GPIO4)
.with_dout(peripherals.GPIO5)
.build();
let data =

View File

@ -8,7 +8,7 @@
#![no_main]
use esp_backtrace as _;
use esp_hal::{gpio::Io, prelude::*, reset::software_reset, uart::Uart};
use esp_hal::{prelude::*, reset::software_reset, uart::Uart};
use esp_ieee802154::{Config, Ieee802154};
use esp_println::println;
@ -16,14 +16,12 @@ use esp_println::println;
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
// Default pins for Uart/Serial communication
cfg_if::cfg_if! {
if #[cfg(feature = "esp32c6")] {
let (mut tx_pin, mut rx_pin) = (io.pins.gpio16, io.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) = (io.pins.gpio24, io.pins.gpio23);
let (mut tx_pin, mut rx_pin) = (peripherals.GPIO24, peripherals.GPIO23);
}
}

View File

@ -28,7 +28,6 @@ use esp_hal::{
delay::Delay,
dma::{Dma, DmaPriority},
dma_rx_stream_buffer,
gpio::Io,
i2c::{
self,
master::{Config, I2c},
@ -46,8 +45,6 @@ use esp_println::{print, println};
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let dma = Dma::new(peripherals.DMA);
let channel = dma.channel0;
@ -55,21 +52,21 @@ fn main() -> ! {
let channel = channel.configure(false, DmaPriority::Priority0);
let cam_siod = io.pins.gpio4;
let cam_sioc = io.pins.gpio5;
let cam_xclk = io.pins.gpio15;
let cam_vsync = io.pins.gpio6;
let cam_href = io.pins.gpio7;
let cam_pclk = io.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(
io.pins.gpio11,
io.pins.gpio9,
io.pins.gpio8,
io.pins.gpio10,
io.pins.gpio12,
io.pins.gpio18,
io.pins.gpio17,
io.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);

View File

@ -27,7 +27,7 @@ use esp_hal::{
delay::Delay,
dma::{Dma, DmaPriority, DmaTxBuf},
dma_tx_buffer,
gpio::{Input, Io, Level, Output, Pull},
gpio::{Input, Level, Output, Pull},
lcd_cam::{
lcd::i8080::{Config, TxEightBits, I8080},
LcdCam,
@ -41,13 +41,11 @@ use esp_println::println;
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let lcd_backlight = io.pins.gpio45;
let lcd_reset = io.pins.gpio4;
let lcd_rs = io.pins.gpio0; // Command/Data selection
let lcd_wr = io.pins.gpio47; // Write clock
let lcd_te = io.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;
@ -63,14 +61,14 @@ fn main() -> ! {
let tear_effect = Input::new(lcd_te, Pull::None);
let tx_pins = TxEightBits::new(
io.pins.gpio9,
io.pins.gpio46,
io.pins.gpio3,
io.pins.gpio8,
io.pins.gpio18,
io.pins.gpio17,
io.pins.gpio16,
io.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);

View File

@ -11,7 +11,6 @@
use esp_backtrace as _;
use esp_hal::{
gpio::Io,
ledc::{
channel::{self, ChannelIFace},
timer::{self, TimerIFace},
@ -26,8 +25,7 @@ use esp_hal::{
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let led = io.pins.gpio0;
let led = peripherals.GPIO0;
let mut ledc = Ledc::new(peripherals.LEDC);

View File

@ -15,7 +15,7 @@
use esp_backtrace as _;
use esp_hal::{
gpio::{lp_io::LowPowerOutput, Io},
gpio::lp_io::LowPowerOutput,
lp_core::{LpCore, LpCoreWakeupSource},
prelude::*,
};
@ -26,8 +26,8 @@ fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
// configure GPIO 1 as LP output pin
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let lp_pin = LowPowerOutput::new(io.pins.gpio1);
let lp_pin = LowPowerOutput::new(peripherals.GPIO1);
let mut lp_core = LpCore::new(peripherals.LP_CORE);
lp_core.stop();

View File

@ -16,7 +16,7 @@
use esp_backtrace as _;
use esp_hal::{
gpio::{lp_io::LowPowerOutputOpenDrain, Io},
gpio::lp_io::LowPowerOutputOpenDrain,
i2c::lp_i2c::LpI2c,
lp_core::{LpCore, LpCoreWakeupSource},
prelude::*,
@ -27,10 +27,8 @@ use esp_println::println;
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let lp_sda = LowPowerOutputOpenDrain::new(io.pins.gpio6);
let lp_scl = LowPowerOutputOpenDrain::new(io.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());

View File

@ -16,10 +16,7 @@
use esp_backtrace as _;
use esp_hal::{
gpio::{
lp_io::{LowPowerInput, LowPowerOutput},
Io,
},
gpio::lp_io::{LowPowerInput, LowPowerOutput},
lp_core::{LpCore, LpCoreWakeupSource},
prelude::*,
uart::{lp_uart::LpUart, Config, Uart},
@ -30,21 +27,19 @@ use esp_println::println;
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
// Set up (HP) UART1:
let mut uart1 = Uart::new_with_config(
peripherals.UART1,
Config::default(),
io.pins.gpio6,
io.pins.gpio7,
peripherals.GPIO6,
peripherals.GPIO7,
)
.unwrap();
// Set up (LP) UART:
let lp_tx = LowPowerOutput::new(io.pins.gpio5);
let lp_rx = LowPowerInput::new(io.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);

View File

@ -11,7 +11,6 @@
use esp_backtrace as _;
use esp_hal::{
gpio::Io,
mcpwm::{operator::PwmPinConfig, timer::PwmWorkingMode, McPwm, PeripheralClockConfig},
prelude::*,
};
@ -20,8 +19,7 @@ use esp_hal::{
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let pin = io.pins.gpio0;
let pin = peripherals.GPIO0;
// initialize peripheral
cfg_if::cfg_if! {

View File

@ -14,7 +14,6 @@ use esp_hal::{
delay::Delay,
dma::{Dma, DmaPriority},
dma_buffers,
gpio::Io,
parl_io::{no_clk_pin, BitPackOrder, ParlIoRxOnly, RxFourBits},
prelude::*,
};
@ -24,14 +23,17 @@ use esp_println::println;
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let (rx_buffer, rx_descriptors, _, _) = dma_buffers!(32000, 0);
let dma = Dma::new(peripherals.DMA);
let dma_channel = dma.channel0;
let mut rx_pins = RxFourBits::new(io.pins.gpio1, io.pins.gpio2, io.pins.gpio3, io.pins.gpio4);
let mut rx_pins = RxFourBits::new(
peripherals.GPIO1,
peripherals.GPIO2,
peripherals.GPIO3,
peripherals.GPIO4,
);
let parl_io = ParlIoRxOnly::new(
peripherals.PARL_IO,

View File

@ -18,7 +18,6 @@ use esp_hal::{
delay::Delay,
dma::{Dma, DmaPriority},
dma_buffers,
gpio::Io,
parl_io::{
BitPackOrder,
ClkOutPin,
@ -35,16 +34,19 @@ use esp_println::println;
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let (_, _, tx_buffer, tx_descriptors) = dma_buffers!(0, 32000);
let dma = Dma::new(peripherals.DMA);
let dma_channel = dma.channel0;
let tx_pins = TxFourBits::new(io.pins.gpio1, io.pins.gpio2, io.pins.gpio3, io.pins.gpio4);
let tx_pins = TxFourBits::new(
peripherals.GPIO1,
peripherals.GPIO2,
peripherals.GPIO3,
peripherals.GPIO4,
);
let mut pin_conf = TxPinConfigWithValidPin::new(tx_pins, io.pins.gpio5);
let mut pin_conf = TxPinConfigWithValidPin::new(tx_pins, peripherals.GPIO5);
let parl_io = ParlIoTxOnly::new(
peripherals.PARL_IO,
@ -54,7 +56,7 @@ fn main() -> ! {
)
.unwrap();
let mut clock_pin = ClkOutPin::new(io.pins.gpio6);
let mut clock_pin = ClkOutPin::new(peripherals.GPIO6);
let mut parl_io_tx = parl_io
.tx

View File

@ -20,7 +20,7 @@ use core::{cell::RefCell, cmp::min, sync::atomic::Ordering};
use critical_section::Mutex;
use esp_backtrace as _;
use esp_hal::{
gpio::{Input, Io, Pull},
gpio::{Input, Pull},
interrupt::Priority,
pcnt::{channel, unit, Pcnt},
prelude::*,
@ -35,8 +35,6 @@ static VALUE: AtomicI32 = AtomicI32::new(0);
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
// Set up a pulse counter:
println!("setup pulse counter unit 0");
let mut pcnt = Pcnt::new(peripherals.PCNT);
@ -50,8 +48,8 @@ fn main() -> ! {
println!("setup channel 0");
let ch0 = &u0.channel0;
let pin_a = Input::new(io.pins.gpio4, Pull::Up);
let pin_b = Input::new(io.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();

View File

@ -32,7 +32,6 @@ use esp_hal::{
delay::Delay,
dma::{Dma, DmaPriority, DmaRxBuf, DmaTxBuf},
dma_buffers,
gpio::Io,
prelude::*,
spi::{
master::{Address, Command, Config, Spi},
@ -46,22 +45,21 @@ use esp_println::{print, println};
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
cfg_if::cfg_if! {
if #[cfg(feature = "esp32")] {
let sclk = io.pins.gpio0;
let miso = io.pins.gpio2;
let mosi = io.pins.gpio4;
let sio2 = io.pins.gpio5;
let sio3 = io.pins.gpio13;
let cs = io.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 = io.pins.gpio0;
let miso = io.pins.gpio1;
let mosi = io.pins.gpio2;
let sio2 = io.pins.gpio3;
let sio3 = io.pins.gpio4;
let cs = io.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;
}
}

View File

@ -14,7 +14,7 @@
use esp_backtrace as _;
use esp_hal::{
delay::Delay,
gpio::{Io, Level, Output},
gpio::{Level, Output},
prelude::*,
rmt::{PulseCode, Rmt, RxChannel, RxChannelConfig, RxChannelCreator},
};
@ -26,8 +26,7 @@ const WIDTH: usize = 80;
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let mut out = Output::new(io.pins.gpio5, Level::Low);
let mut out = Output::new(peripherals.GPIO5, Level::Low);
cfg_if::cfg_if! {
if #[cfg(feature = "esp32h2")] {
@ -47,11 +46,11 @@ fn main() -> ! {
cfg_if::cfg_if! {
if #[cfg(any(feature = "esp32", feature = "esp32s2"))] {
let mut channel = rmt.channel0.configure(io.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(io.pins.gpio4, rx_config).unwrap();
let mut channel = rmt.channel7.configure(peripherals.GPIO4, rx_config).unwrap();
} else {
let mut channel = rmt.channel2.configure(io.pins.gpio4, rx_config).unwrap();
let mut channel = rmt.channel2.configure(peripherals.GPIO4, rx_config).unwrap();
}
}

View File

@ -13,7 +13,6 @@
use esp_backtrace as _;
use esp_hal::{
delay::Delay,
gpio::Io,
prelude::*,
rmt::{PulseCode, Rmt, TxChannel, TxChannelConfig, TxChannelCreator},
};
@ -22,8 +21,6 @@ use esp_hal::{
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
cfg_if::cfg_if! {
if #[cfg(feature = "esp32h2")] {
let freq = 32.MHz();
@ -39,7 +36,10 @@ fn main() -> ! {
..TxChannelConfig::default()
};
let mut channel = rmt.channel0.configure(io.pins.gpio4, tx_config).unwrap();
let mut channel = rmt
.channel0
.configure(peripherals.GPIO4, tx_config)
.unwrap();
let delay = Delay::new();

View File

@ -13,7 +13,6 @@ use critical_section::Mutex;
use esp_backtrace as _;
use esp_hal::{
delay::Delay,
gpio::Io,
prelude::*,
uart::{AtCmdConfig, Config, Uart, UartInterrupt},
Blocking,
@ -27,22 +26,20 @@ fn main() -> ! {
let delay = Delay::new();
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
// Default pins for Uart/Serial communication
cfg_if::cfg_if! {
if #[cfg(feature = "esp32")] {
let (tx_pin, rx_pin) = (io.pins.gpio1, io.pins.gpio3);
let (tx_pin, rx_pin) = (peripherals.GPIO1, peripherals.GPIO3);
} else if #[cfg(feature = "esp32c2")] {
let (tx_pin, rx_pin) = (io.pins.gpio20, io.pins.gpio19);
let (tx_pin, rx_pin) = (peripherals.GPIO20, peripherals.GPIO19);
} else if #[cfg(feature = "esp32c3")] {
let (tx_pin, rx_pin) = (io.pins.gpio21, io.pins.gpio20);
let (tx_pin, rx_pin) = (peripherals.GPIO21, peripherals.GPIO20);
} else if #[cfg(feature = "esp32c6")] {
let (tx_pin, rx_pin) = (io.pins.gpio16, io.pins.gpio17);
let (tx_pin, rx_pin) = (peripherals.GPIO16, peripherals.GPIO17);
} else if #[cfg(feature = "esp32h2")] {
let (tx_pin, rx_pin) = (io.pins.gpio24, io.pins.gpio23);
let (tx_pin, rx_pin) = (peripherals.GPIO24, peripherals.GPIO23);
} else if #[cfg(any(feature = "esp32s2", feature = "esp32s3"))] {
let (tx_pin, rx_pin) = (io.pins.gpio43, io.pins.gpio44);
let (tx_pin, rx_pin) = (peripherals.GPIO43, peripherals.GPIO44);
}
}
let config = Config::default().rx_fifo_full_threshold(30);

View File

@ -14,7 +14,7 @@ use esp_backtrace as _;
use esp_hal::{
delay::Delay,
entry,
gpio::{Input, Io, Pull},
gpio::{Input, Pull},
rtc_cntl::{
get_reset_reason,
get_wakeup_cause,
@ -32,8 +32,7 @@ fn main() -> ! {
let mut rtc = Rtc::new(peripherals.LPWR);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let ext0_pin = Input::new(io.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);

View File

@ -14,7 +14,7 @@ use esp_backtrace as _;
use esp_hal::{
delay::Delay,
entry,
gpio::{Input, Io, Pull, RtcPin},
gpio::{Input, Pull, RtcPin},
peripheral::Peripheral,
rtc_cntl::{
get_reset_reason,
@ -33,9 +33,8 @@ fn main() -> ! {
let mut rtc = Rtc::new(peripherals.LPWR);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let pin_0 = Input::new(io.pins.gpio4, Pull::None);
let mut pin_2 = io.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);

View File

@ -15,7 +15,7 @@ use esp_backtrace as _;
use esp_hal::{
delay::Delay,
entry,
gpio::{Input, Io, Pull, RtcPinWithResistors},
gpio::{Input, Pull, RtcPinWithResistors},
peripheral::Peripheral,
rtc_cntl::{
get_reset_reason,
@ -34,9 +34,8 @@ fn main() -> ! {
let mut rtc = Rtc::new(peripherals.LPWR);
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let pin2 = Input::new(io.pins.gpio2, Pull::None);
let mut pin3 = io.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);

View File

@ -19,7 +19,7 @@ use esp_hal::{
delay::Delay,
entry,
gpio,
gpio::{Input, Io, Pull},
gpio::{Input, Pull},
peripheral::Peripheral,
rtc_cntl::{
get_reset_reason,
@ -36,7 +36,6 @@ use esp_println::println;
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
let mut rtc = Rtc::new(peripherals.LPWR);
println!("up and runnning!");
@ -50,16 +49,16 @@ fn main() -> ! {
cfg_if::cfg_if! {
if #[cfg(any(feature = "esp32c3", feature = "esp32c2"))] {
let pin2 = Input::new(io.pins.gpio2, Pull::None);
let mut pin3 = io.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(io.pins.gpio17, Pull::None);
let mut pin18 = io.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),

Some files were not shown because too many files have changed in this diff Show More