diff --git a/esp-hal/CHANGELOG.md b/esp-hal/CHANGELOG.md index 65fd89f3a..911ca79c4 100644 --- a/esp-hal/CHANGELOG.md +++ b/esp-hal/CHANGELOG.md @@ -10,6 +10,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0 ### Added - Added new `Io::new_no_bind_interrupt` constructor (#1861) +- Added touch pad support for esp32 (#1873) ### Changed diff --git a/esp-hal/src/gpio/mod.rs b/esp-hal/src/gpio/mod.rs index 8c72d388e..762843bc3 100644 --- a/esp-hal/src/gpio/mod.rs +++ b/esp-hal/src/gpio/mod.rs @@ -66,6 +66,8 @@ use crate::{ private, InterruptConfigurable, }; +#[cfg(touch)] +pub(crate) use crate::{touch_common, touch_into}; pub mod any_pin; pub mod dummy_pin; @@ -395,6 +397,21 @@ pub trait AnalogPin: Pin { fn set_analog(&self, _: private::Internal); } +/// Trait implemented by pins which can be used as Touchpad pins +pub trait TouchPin: Pin { + /// Configure the pin for analog operation + fn set_touch(&self, _: private::Internal); + + /// Reads the pin's touch measurement register + fn get_touch_measurement(&self, _: private::Internal) -> u16; + + /// Maps the pin nr to the touch pad nr + fn get_touch_nr(&self, _: private::Internal) -> u8; + + /// Set a pins touch threshold for interrupts. + fn set_threshold(&self, threshold: u16, _: private::Internal); +} + #[doc(hidden)] pub trait CreateErasedPin: Pin { fn erased_pin(&self, _: private::Internal) -> ErasedPin; @@ -619,6 +636,9 @@ pub trait IsInputPin: PinType {} #[doc(hidden)] pub trait IsAnalogPin: PinType {} +#[doc(hidden)] +pub trait IsTouchPin: PinType {} + #[doc(hidden)] pub struct InputOutputPinType; @@ -631,6 +651,9 @@ pub struct InputOutputAnalogPinType; #[doc(hidden)] pub struct InputOnlyAnalogPinType; +#[doc(hidden)] +pub struct InputOutputAnalogTouchPinType; + impl PinType for InputOutputPinType {} impl IsOutputPin for InputOutputPinType {} impl IsInputPin for InputOutputPinType {} @@ -647,6 +670,12 @@ impl PinType for InputOnlyAnalogPinType {} impl IsInputPin for InputOnlyAnalogPinType {} impl IsAnalogPin for InputOnlyAnalogPinType {} +impl PinType for InputOutputAnalogTouchPinType {} +impl IsOutputPin for InputOutputAnalogTouchPinType {} +impl IsInputPin for InputOutputAnalogTouchPinType {} +impl IsAnalogPin for InputOutputAnalogTouchPinType {} +impl IsTouchPin for InputOutputAnalogTouchPinType {} + /// GPIO pin pub struct GpioPin; @@ -1182,6 +1211,29 @@ where } } +#[cfg(touch)] +impl TouchPin for GpioPin +where + Self: GpioProperties, + ::PinType: IsTouchPin, +{ + fn set_touch(&self, _: private::Internal) { + crate::soc::gpio::internal_into_touch(GPIONUM); + } + + fn get_touch_measurement(&self, _: private::Internal) -> u16 { + crate::soc::gpio::internal_get_touch_measurement(GPIONUM) + } + + fn get_touch_nr(&self, _: private::Internal) -> u8 { + crate::soc::gpio::internal_get_touch_nr(GPIONUM) + } + + fn set_threshold(&self, threshold: u16, _: private::Internal) { + crate::soc::gpio::internal_set_threshold(GPIONUM, threshold) + } +} + /// General Purpose Input/Output driver pub struct Io { _io_mux: IO_MUX, @@ -1620,6 +1672,156 @@ macro_rules! analog { } } +/// normal touch pin initialization. This is separate from touch_common, as we +/// need to handle some touch_pads differently +#[doc(hidden)] +#[macro_export] +macro_rules! touch_into { + ( + $( ( $touch_num:expr, $pin_num:expr, $rtc_pin:expr, $touch_thres_reg:expr, $touch_thres_field:expr , true ) )+ + --- + $( ( $touch_numx:expr, $pin_numx:expr, $rtc_pinx:expr, $touch_thres_regx:expr , $touch_thres_fieldx:expr , false ) )* + ) => { + pub(crate) fn internal_into_touch(pin: u8) { + use $crate::peripherals::{GPIO, RTC_IO, SENS}; + + let rtcio = unsafe { &*RTC_IO::ptr() }; + let sens = unsafe { &*SENS::ptr() }; + let gpio = unsafe { &*GPIO::ptr() }; + + match pin { + $( + $pin_num => { + paste::paste! { + // Pad to normal mode (not open-drain) + gpio.pin($rtc_pin).write(|w| w.pad_driver().clear_bit()); + + // clear output + rtcio.enable_w1tc().write(|w| unsafe { w.enable_w1tc().bits(1 << $rtc_pin) }); + sens + . $touch_thres_reg () + .write(|w| unsafe { + w. $touch_thres_field ().bits( + 0b0 // Default: 0 for esp32 gets overridden later anyway. + ) + }); + + rtcio.[< touch_pad $touch_num >]().write(|w| unsafe { + w + .xpd().set_bit() + // clear input_enable + .fun_ie().clear_bit() + // Connect pin to analog / RTC module instead of standard GPIO + .mux_sel().set_bit() + // Disable pull-up and pull-down resistors on the pin + .rue().clear_bit() + .rde().clear_bit() + .tie_opt().clear_bit() + // Select function "RTC function 1" (GPIO) for analog use + .fun_sel().bits(0b00) + }); + + sens.sar_touch_enable().modify(|r, w| unsafe { + w + // enable the pin + .touch_pad_worken().bits( + r.touch_pad_worken().bits() | ( 1 << [< $touch_num >] ) + ) + }); + } + } + )+ + + $( + $pin_numx => { + paste::paste! { + // Pad to normal mode (not open-drain) + gpio.pin($rtc_pinx).write(|w| w.pad_driver().clear_bit()); + + // clear output + rtcio.enable_w1tc().write(|w| unsafe { w.enable_w1tc().bits(1 << $rtc_pinx) }); + sens + . $touch_thres_regx () + .write(|w| unsafe { + w. $touch_thres_fieldx ().bits( + 0b0 // Default: 0 for esp32 gets overridden later anyway. + ) + }); + + rtcio.[< touch_pad $touch_numx >]().write(|w| + w + .xpd().set_bit() + .tie_opt().clear_bit() + ); + + sens.sar_touch_enable().modify(|r, w| unsafe { + w + // enable the pin + .touch_pad_worken().bits( + r.touch_pad_worken().bits() | ( 1 << [< $touch_numx >] ) + ) + }); + } + } + )* + _ => unreachable!(), + } + } + }; +} + +/// Common functionality for all touch pads +#[doc(hidden)] +#[macro_export] +macro_rules! touch_common { + ( + $( + ( + $touch_num:expr, $pin_num:expr, $touch_out_reg:expr, $meas_field: expr, $touch_thres_reg:expr, $touch_thres_field:expr + ) + )+ + ) => { + pub(crate) fn internal_get_touch_measurement(pin: u8) -> u16 { + match pin { + $( + $pin_num => { + paste::paste! { + unsafe { &* $crate::peripherals::SENS::ptr() } + . $touch_out_reg () + .read() + . $meas_field () + .bits() + } + }, + )+ + _ => unreachable!(), + } + } + pub(crate) fn internal_get_touch_nr(pin: u8) -> u8 { + match pin { + $($pin_num => $touch_num,)+ + _ => unreachable!(), + } + } + pub(crate) fn internal_set_threshold(pin: u8, threshold: u16) { + match pin { + $( + $pin_num => { + paste::paste! { + unsafe { &* $crate::peripherals::SENS::ptr() } + . $touch_thres_reg () + .write(|w| unsafe { + w. $touch_thres_field ().bits(threshold) + }); + } + }, + )+ + _ => unreachable!(), + } + } + }; +} + /// GPIO output driver. pub struct Output<'d, P> { pin: PeripheralRef<'d, P>, diff --git a/esp-hal/src/lib.rs b/esp-hal/src/lib.rs index e9ae04b8f..ee1a1490c 100644 --- a/esp-hal/src/lib.rs +++ b/esp-hal/src/lib.rs @@ -229,6 +229,8 @@ pub mod system; pub mod time; #[cfg(any(systimer, timg0, timg1))] pub mod timer; +#[cfg(touch)] +pub mod touch; #[cfg(trace0)] pub mod trace; #[cfg(any(twai0, twai1))] diff --git a/esp-hal/src/soc/esp32/gpio.rs b/esp-hal/src/soc/esp32/gpio.rs index cf7b971b5..fb8b29ed1 100644 --- a/esp-hal/src/soc/esp32/gpio.rs +++ b/esp-hal/src/soc/esp32/gpio.rs @@ -871,11 +871,11 @@ pub(crate) fn errata36(pin_num: u8, pull_up: Option, pull_down: Option EMAC_TX_CLK) (1 => CLK_OUT1)) + (0, 0, InputOutputAnalogTouch (5 => EMAC_TX_CLK) (1 => CLK_OUT1)) (1, 0, InputOutput (5 => EMAC_RXD2) (0 => U0TXD 1 => CLK_OUT3)) - (2, 0, InputOutputAnalog (1 => HSPIWP 3 => HS2_DATA0 4 => SD_DATA0) (3 => HS2_DATA0 4 => SD_DATA0)) + (2, 0, InputOutputAnalogTouch (1 => HSPIWP 3 => HS2_DATA0 4 => SD_DATA0) (3 => HS2_DATA0 4 => SD_DATA0)) (3, 0, InputOutput (0 => U0RXD) (1 => CLK_OUT2)) - (4, 0, InputOutputAnalog (1 => HSPIHD 3 => HS2_DATA1 4 => SD_DATA1 5 => EMAC_TX_ER) (3 => HS2_DATA1 4 => SD_DATA1)) + (4, 0, InputOutputAnalogTouch (1 => HSPIHD 3 => HS2_DATA1 4 => SD_DATA1 5 => EMAC_TX_ER) (3 => HS2_DATA1 4 => SD_DATA1)) (5, 0, InputOutput (1 => VSPICS0 3 => HS1_DATA6 5 => EMAC_RX_CLK) (3 => HS1_DATA6)) (6, 0, InputOutput (4 => U1CTS) (0 => SD_CLK 1 => SPICLK 3 => HS1_CLK)) (7, 0, InputOutput (0 => SD_DATA0 1 => SPIQ 3 => HS1_DATA0) (0 => SD_DATA0 1 => SPIQ 3 => HS1_DATA0 4 => U2RTS)) @@ -883,10 +883,10 @@ crate::gpio::gpio! { (9, 0, InputOutput (0 => SD_DATA2 1 => SPIHD 3 => HS1_DATA2 4 => U1RXD) (0 => SD_DATA2 1 => SPIHD 3 => HS1_DATA2)) (10, 0, InputOutput ( 0 => SD_DATA3 1 => SPIWP 3 => HS1_DATA3) (0 => SD_DATA3 1 => SPIWP 3 => HS1_DATA3 4 => U1TXD)) (11, 0, InputOutput ( 1 => SPICS0) (0 => SD_CMD 1 => SPICS0 3 => HS1_CMD 4 => U1RTS)) - (12, 0, InputOutputAnalog (0 => MTDI 1 => HSPIQ 3 => HS2_DATA2 4 => SD_DATA2) (1 => HSPIQ 3 => HS2_DATA2 4 => SD_DATA2 5 => EMAC_TXD3)) - (13, 0, InputOutputAnalog (0 => MTCK 1 => HSPID 3 => HS2_DATA3 4 => SD_DATA3) (1 => HSPID 3 => HS2_DATA3 4 => SD_DATA3 5 => EMAC_RX_ER)) - (14, 0, InputOutputAnalog (0 => MTMS 1 => HSPICLK) (1 => HSPICLK 3 => HS2_CLK 4 => SD_CLK 5 => EMAC_TXD2)) - (15, 0, InputOutputAnalog (1 => HSPICS0 5 => EMAC_RXD3) (0 => MTDO 1 => HSPICS0 3 => HS2_CMD 4 => SD_CMD)) + (12, 0, InputOutputAnalogTouch (0 => MTDI 1 => HSPIQ 3 => HS2_DATA2 4 => SD_DATA2) (1 => HSPIQ 3 => HS2_DATA2 4 => SD_DATA2 5 => EMAC_TXD3)) + (13, 0, InputOutputAnalogTouch (0 => MTCK 1 => HSPID 3 => HS2_DATA3 4 => SD_DATA3) (1 => HSPID 3 => HS2_DATA3 4 => SD_DATA3 5 => EMAC_RX_ER)) + (14, 0, InputOutputAnalogTouch (0 => MTMS 1 => HSPICLK) (1 => HSPICLK 3 => HS2_CLK 4 => SD_CLK 5 => EMAC_TXD2)) + (15, 0, InputOutputAnalogTouch (1 => HSPICS0 5 => EMAC_RXD3) (0 => MTDO 1 => HSPICS0 3 => HS2_CMD 4 => SD_CMD)) (16, 0, InputOutput (3 => HS1_DATA4 4 => U2RXD) (3 => HS1_DATA4 5 => EMAC_CLK_OUT)) (17, 0, InputOutput (3 => HS1_DATA5) (3 => HS1_DATA5 4 => U2TXD 5 => EMAC_CLK_180)) (18, 0, InputOutput (1 => VSPICLK 3 => HS1_DATA7) (1 => VSPICLK 3 => HS1_DATA7)) @@ -898,7 +898,7 @@ crate::gpio::gpio! { (24, 0, InputOutput) (25, 0, InputOutputAnalog (5 => EMAC_RXD0) ()) (26, 0, InputOutputAnalog (5 => EMAC_RXD1) ()) - (27, 0, InputOutputAnalog (5 => EMAC_RX_DV) ()) + (27, 0, InputOutputAnalogTouch (5 => EMAC_RX_DV) ()) (32, 1, InputOutputAnalog) (33, 1, InputOutputAnalog) (34, 1, InputOnlyAnalog) @@ -951,6 +951,35 @@ crate::gpio::rtc_pins! { (27, 17, touch_pad7(), "", touch_pad7_hold_force, rue, rde ) } +crate::gpio::touch_into! { + // (touch_nr, pin_nr, rtc_pin, touch_comb_reg_nr, normal_pin) + (0, 4, 10, sar_touch_thres1, touch_out_th0, true ) + (1, 0, 11, sar_touch_thres1, touch_out_th1, true ) + (2, 2, 12, sar_touch_thres2, touch_out_th2, true ) + (3, 15, 13, sar_touch_thres2, touch_out_th3, true ) + (4, 13, 14, sar_touch_thres3, touch_out_th4, true ) + (5, 12, 15, sar_touch_thres3, touch_out_th5, true ) + (6, 14, 16, sar_touch_thres4, touch_out_th6, true ) + (7, 27, 17, sar_touch_thres4, touch_out_th7, true ) + --- + (8, 33, 8, sar_touch_thres5, touch_out_th8, false ) + (9, 32, 9, sar_touch_thres5, touch_out_th9, false ) +} + +crate::gpio::touch_common! { + // (touch_nr, pin_nr, touch_out_reg, touch_thres_reg ) + (0, 4, sar_touch_out1, touch_meas_out0, sar_touch_thres1, touch_out_th0) + (1, 0, sar_touch_out1, touch_meas_out1, sar_touch_thres1, touch_out_th1) + (2, 2, sar_touch_out2, touch_meas_out2, sar_touch_thres2, touch_out_th2) + (3, 15, sar_touch_out2, touch_meas_out3, sar_touch_thres2, touch_out_th3) + (4, 13, sar_touch_out3, touch_meas_out4, sar_touch_thres3, touch_out_th4) + (5, 12, sar_touch_out3, touch_meas_out5, sar_touch_thres3, touch_out_th5) + (6, 14, sar_touch_out4, touch_meas_out6, sar_touch_thres4, touch_out_th6) + (7, 27, sar_touch_out4, touch_meas_out7, sar_touch_thres4, touch_out_th7) + (8, 33, sar_touch_out5, touch_meas_out8, sar_touch_thres5, touch_out_th8) + (9, 32, sar_touch_out5, touch_meas_out9, sar_touch_thres5, touch_out_th9) +} + impl InterruptStatusRegisterAccess for InterruptStatusRegisterAccessBank0 { fn pro_cpu_interrupt_status_read() -> u32 { unsafe { &*GPIO::PTR }.pcpu_int().read().bits() diff --git a/esp-hal/src/soc/esp32/peripherals.rs b/esp-hal/src/soc/esp32/peripherals.rs index 11a2d837f..fe2be78c2 100644 --- a/esp-hal/src/soc/esp32/peripherals.rs +++ b/esp-hal/src/soc/esp32/peripherals.rs @@ -65,6 +65,7 @@ crate::peripherals! { SYSTEM <= DPORT, TIMG0 <= TIMG0, TIMG1 <= TIMG1, + TOUCH <= virtual, TWAI0 <= TWAI0, UART0 <= UART0, UART1 <= UART1, diff --git a/esp-hal/src/touch.rs b/esp-hal/src/touch.rs new file mode 100644 index 000000000..010f870c1 --- /dev/null +++ b/esp-hal/src/touch.rs @@ -0,0 +1,600 @@ +//! # Capacitive Touch Sensor +//! +//! ## Overview +//! +//! The touch sensor peripheral allows for cheap and robust user interfaces by +//! e.g., dedicating a part of the pcb as touch button. +//! +//! ## Examples +//! +//! ```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 = Touch::continous_mode(peripherals.TOUCH, None); +//! let mut touchpad = TouchPad::new(touch_pin0, &touch); +//! // ... give the peripheral some time for the measurement +//! let touch_val = touchpad.read(); +//! # } +//! ``` +//! +//! ## Implementation State: +//! +//! Mostly feature complete, missing: +//! +//! - Touch sensor slope control +//! - Deep Sleep support (wakeup from Deep Sleep) + +#![deny(missing_docs)] + +use core::marker::PhantomData; + +use crate::{ + gpio::TouchPin, + peripheral::{Peripheral, PeripheralRef}, + peripherals::{RTC_CNTL, SENS, TOUCH}, + private::{Internal, Sealed}, + Blocking, + Mode, +}; +#[cfg(feature = "async")] +use crate::{rtc_cntl::Rtc, Async, InterruptConfigurable}; + +/// A marker trait describing the mode the touch pad is set to. +pub trait TouchMode: Sealed {} + +/// Marker struct for the touch peripherals manual trigger mode. In the +/// technical reference manual, this is referred to as "start FSM via software". +#[derive(Debug)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +pub struct OneShot; + +/// Marker struct for the touch peripherals continous reading mode. In the +/// technical reference manual, this is referred to as "start FSM via timer". +#[derive(Debug)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +pub struct Continous; + +impl TouchMode for OneShot {} +impl TouchMode for Continous {} +impl Sealed for OneShot {} +impl Sealed for Continous {} + +/// Touchpad threshold type. +#[derive(Debug, Copy, Clone)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +pub enum ThresholdMode { + /// Pad is considered touched if value is greater than threshold. + GreaterThan, + /// Pad is considered touched if value is less than threshold. + LessThan, +} + +/// Configurations for the touch pad driver +#[derive(Debug, Copy, Clone, Default)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +pub struct TouchConfig { + /// The [`ThresholdMode`] for the pads. Defaults to + /// `ThresholdMode::LessThan` + pub threshold_mode: Option, + /// Duration of a single measurement (in cycles of the 8 MHz touch clock). + /// Defaults to `0x7fff` + pub measurement_duration: Option, + /// Sleep cycles for the touch timer in [`Continous`]-mode. Defaults to + /// `0x100` + pub sleep_cycles: Option, +} + +/// This struct marks a successfully initialized touch peripheral +pub struct Touch<'d, TOUCHMODE: TouchMode, MODE: Mode> { + _inner: PeripheralRef<'d, TOUCH>, + _touch_mode: PhantomData, + _mode: PhantomData, +} +impl<'d, TOUCHMODE: TouchMode, MODE: Mode> Touch<'d, TOUCHMODE, MODE> { + /// Common initialization of the touch peripheral. + fn initialize_common(config: Option) { + let rtccntl = unsafe { &*RTC_CNTL::ptr() }; + let sens = unsafe { &*SENS::ptr() }; + + let mut threshold_mode = false; + let mut meas_dur = 0x7fff; + + if let Some(config) = config { + threshold_mode = match config.threshold_mode { + Some(ThresholdMode::LessThan) => false, + Some(ThresholdMode::GreaterThan) => true, + None => false, + }; + if let Some(dur) = config.measurement_duration { + meas_dur = dur; + } + } + + // stop touch fsm + rtccntl + .state0() + .write(|w| w.touch_slp_timer_en().clear_bit()); + // Disable touch interrupt + rtccntl.int_ena().write(|w| w.touch().clear_bit()); + // Clear pending interrupts + rtccntl.int_clr().write(|w| w.touch().bit(true)); + + // Disable all interrupts and touch pads + sens.sar_touch_enable().write(|w| unsafe { + w.touch_pad_outen1() + .bits(0b0) + .touch_pad_outen2() + .bits(0b0) + .touch_pad_worken() + .bits(0b0) + }); + + sens.sar_touch_ctrl1().write(|w| unsafe { + w + // Default to trigger when touch is below threshold + .touch_out_sel() + .bit(threshold_mode) + // Interrupt only on set 1 + .touch_out_1en() + .set_bit() + .touch_meas_delay() + .bits(meas_dur) + // TODO Chip Specific + .touch_xpd_wait() + .bits(0xff) + }); + } + + /// Common parts of the continous mode initialization. + fn initialize_common_continoous(config: Option) { + let rtccntl = unsafe { &*RTC_CNTL::ptr() }; + let sens = unsafe { &*SENS::ptr() }; + + // Default nr of sleep cycles from IDF + let mut sleep_cyc = 0x1000; + if let Some(config) = config { + if let Some(slp) = config.sleep_cycles { + sleep_cyc = slp; + } + } + + Self::initialize_common(config); + + sens.sar_touch_ctrl2().write(|w| unsafe { + w + // Reset existing touch measurements + .touch_meas_en_clr() + .set_bit() + .touch_sleep_cycles() + .bits(sleep_cyc) + // Configure FSM for timer mode + .touch_start_fsm_en() + .set_bit() + .touch_start_force() + .clear_bit() + }); + + // start touch fsm + rtccntl.state0().write(|w| w.touch_slp_timer_en().set_bit()); + } +} +// Async mode and OneShot does not seem to be a sensible combination.... +impl<'d> Touch<'d, OneShot, Blocking> { + /// Initializes the touch peripheral and returns this marker struct. + /// Optionally accepts configuration options. + /// + /// ## Example + /// + /// ```rust, no_run + #[doc = crate::before_snippet!()] + /// # use esp_hal::touch::{Touch, TouchConfig}; + /// let touch_cfg = Some(TouchConfig { + /// measurement_duration: Some(0x2000), + /// ..Default::default() + /// }); + /// let touch = Touch::one_shot_mode(peripherals.TOUCH, touch_cfg); + /// # } + /// ``` + pub fn one_shot_mode( + touch_peripheral: impl Peripheral

+ 'd, + config: Option, + ) -> Self { + crate::into_ref!(touch_peripheral); + let rtccntl = unsafe { &*RTC_CNTL::ptr() }; + let sens = unsafe { &*SENS::ptr() }; + + // Default nr of sleep cycles from IDF + let mut sleep_cyc = 0x1000; + if let Some(config) = config { + if let Some(slp) = config.sleep_cycles { + sleep_cyc = slp; + } + } + + Self::initialize_common(config); + + sens.sar_touch_ctrl2().write(|w| unsafe { + w + // Reset existing touch measurements + .touch_meas_en_clr() + .set_bit() + .touch_sleep_cycles() + .bits(sleep_cyc) + // Configure FSM for SW mode + .touch_start_fsm_en() + .set_bit() + .touch_start_en() + .clear_bit() + .touch_start_force() + .set_bit() + }); + + // start touch fsm + rtccntl.state0().write(|w| w.touch_slp_timer_en().set_bit()); + + Self { + _inner: touch_peripheral, + _mode: PhantomData, + _touch_mode: PhantomData, + } + } +} +impl<'d> Touch<'d, Continous, Blocking> { + /// Initializes the touch peripheral in continous mode and returns this + /// marker struct. Optionally accepts configuration options. + /// + /// ## Example + /// + /// ```rust, no_run + #[doc = crate::before_snippet!()] + /// # use esp_hal::touch::{Touch, TouchConfig}; + /// let touch_cfg = Some(TouchConfig { + /// measurement_duration: Some(0x3000), + /// ..Default::default() + /// }); + /// let touch = Touch::continous_mode(peripherals.TOUCH, touch_cfg); + /// # } + /// ``` + pub fn continous_mode( + touch_peripheral: impl Peripheral

+ 'd, + config: Option, + ) -> Self { + crate::into_ref!(touch_peripheral); + + Self::initialize_common_continoous(config); + + Self { + _inner: touch_peripheral, + _mode: PhantomData, + _touch_mode: PhantomData, + } + } +} +#[cfg(feature = "async")] +impl<'d> Touch<'d, Continous, Async> { + /// Initializes the touch peripheral in continous async mode and returns + /// this marker struct. + /// + /// ## Warning: + /// + /// This uses [`RTC_CORE`](crate::peripherals::Interrupt::RTC_CORE) + /// interrupts under the hood. So the whole async part breaks if you install + /// an interrupt handler with [`Rtc::set_interrupt_handler()`][1]. + /// + /// [1]: ../rtc_cntl/struct.Rtc.html#method.set_interrupt_handler + /// + /// ## Parameters: + /// + /// - `rtc`: The RTC peripheral is needed to configure the required + /// interrupts. + /// - `config`: Optional configuration options. + /// + /// ## Example + /// + /// ```rust, no_run + #[doc = crate::before_snippet!()] + /// # use esp_hal::touch::{Touch, TouchConfig}; + /// let mut rtc = Rtc::new(peripherals.LPWR); + /// let touch = Touch::async_mode(peripherals.TOUCH, &mut rtc, None); + /// # } + /// ``` + pub fn async_mode( + touch_peripheral: impl Peripheral

+ 'd, + rtc: &mut Rtc, + config: Option, + ) -> Self { + crate::into_ref!(touch_peripheral); + + Self::initialize_common_continoous(config); + + rtc.set_interrupt_handler(asynch::handle_touch_interrupt); + + Self { + _inner: touch_peripheral, + _mode: PhantomData, + _touch_mode: PhantomData, + } + } +} + +/// A pin that is configured as a TouchPad. +pub struct TouchPad { + pin: P, + _touch_mode: PhantomData, + _mode: PhantomData, +} +impl TouchPad { + /// (Re-)Start a touch measurement on the pin. You can get the result by + /// calling [`read`](Self::read) once it is finished. + pub fn start_measurement(&mut self) { + unsafe { &*crate::peripherals::RTC_IO::ptr() } + .touch_pad2() + .write(|w| unsafe { + w.start() + .set_bit() + .xpd() + .set_bit() + // clear input_enable + .fun_ie() + .clear_bit() + // Connect pin to analog / RTC module instead of standard GPIO + .mux_sel() + .set_bit() + // Disable pull-up and pull-down resistors on the pin + .rue() + .clear_bit() + .rde() + .clear_bit() + .tie_opt() + .clear_bit() + .to_gpio() + .set_bit() + // Select function "RTC function 1" (GPIO) for analog use + .fun_sel() + .bits(0b00) + }); + + unsafe { &*crate::peripherals::SENS::PTR } + .sar_touch_ctrl2() + .modify(|_, w| w.touch_start_en().clear_bit()); + unsafe { &*crate::peripherals::SENS::PTR } + .sar_touch_ctrl2() + .modify(|_, w| w.touch_start_en().set_bit()); + } +} +impl TouchPad { + /// Construct a new instance of [`TouchPad`]. + /// + /// ## Parameters: + /// - `pin`: The pin that gets configured as touch pad + /// - `touch`: The [`Touch`] struct indicating that touch is configured. + pub fn new(pin: P, _touch: &Touch) -> Self { + // TODO revert this on drop + pin.set_touch(Internal); + + Self { + pin, + _mode: PhantomData, + _touch_mode: PhantomData, + } + } + + /// Read the current touch pad capacitance counter. + /// + /// Usually a lower value means higher capacitance, thus indicating touch + /// event. + /// + /// Returns `None` if the value is not yet ready. (Note: Measurement must be + /// started manually with [`start_measurement`](Self::start_measurement) if + /// the touch peripheral is in [`OneShot`] mode). + pub fn try_read(&mut self) -> Option { + if unsafe { &*crate::peripherals::SENS::ptr() } + .sar_touch_ctrl2() + .read() + .touch_meas_done() + .bit_is_set() + { + Some(self.pin.get_touch_measurement(Internal)) + } else { + None + } + } +} +impl TouchPad { + /// Blocking read of the current touch pad capacitance counter. + /// + /// Usually a lower value means higher capacitance, thus indicating touch + /// event. + /// + /// ## Note for [`OneShot`] mode: + /// + /// This function might block forever, if + /// [`start_measurement`](Self::start_measurement) was not called before. As + /// measurements are not cleared, the touch values might also be + /// outdated, if it has been some time since the last call to that + /// function. + pub fn read(&mut self) -> u16 { + while unsafe { &*crate::peripherals::SENS::ptr() } + .sar_touch_ctrl2() + .read() + .touch_meas_done() + .bit_is_clear() + {} + self.pin.get_touch_measurement(Internal) + } + + /// Enables the touch_pad interrupt. + /// + /// The raised interrupt is actually + /// [`RTC_CORE`](crate::peripherals::Interrupt::RTC_CORE). A handler can + /// be installed with [`Rtc::set_interrupt_handler()`][1]. + /// + /// [1]: ../rtc_cntl/struct.Rtc.html#method.set_interrupt_handler + /// + /// ## Parameters: + /// - `threshold`: The threshold above/below which the pin is considered + /// touched. Above/below depends on the configuration of `touch` in + /// [`new`](Self::new) (defaults to below). + /// + /// ## Example + pub fn enable_interrupt(&mut self, threshold: u16) { + self.pin.set_threshold(threshold, Internal); + internal_enable_interrupt(self.pin.get_touch_nr(Internal)) + } + + /// Disables the touch pad's interrupt. + /// + /// If no other touch pad interrupts are active, the touch interrupt is + /// disabled completely. + pub fn disable_interrupt(&mut self) { + internal_disable_interrupt(self.pin.get_touch_nr(Internal)) + } + + /// Clears a pending touch interrupt. + /// + /// ## Note on interrupt clearing behaviour: + /// + /// There is only a single interrupt for the touch pad. + /// [`is_interrupt_set`](Self::is_interrupt_set) can be used to check + /// which pins are touchted. However, this function clears the interrupt + /// status for all pins. So only call it when all pins are handled. + pub fn clear_interrupt(&mut self) { + internal_clear_interrupt() + } + + /// Checks if the pad is touched, based on the configured threshold value. + pub fn is_interrupt_set(&mut self) -> bool { + internal_is_interrupt_set(self.pin.get_touch_nr(Internal)) + } +} + +fn internal_enable_interrupt(touch_nr: u8) { + let rtccntl = unsafe { &*RTC_CNTL::ptr() }; + // enable touch interrupts + rtccntl.int_ena().write(|w| w.touch().set_bit()); + + let sens = unsafe { &*SENS::ptr() }; + sens.sar_touch_enable().modify(|r, w| unsafe { + w.touch_pad_outen1() + .bits(r.touch_pad_outen1().bits() | 1 << touch_nr) + }); +} + +fn internal_disable_interrupt(touch_nr: u8) { + let sens = unsafe { &*SENS::ptr() }; + sens.sar_touch_enable().modify(|r, w| unsafe { + w.touch_pad_outen1() + .bits(r.touch_pad_outen1().bits() & !(1 << touch_nr)) + }); + if sens.sar_touch_enable().read().touch_pad_outen1().bits() == 0 { + let rtccntl = unsafe { &*RTC_CNTL::ptr() }; + rtccntl.int_ena().write(|w| w.touch().clear_bit()); + } +} + +#[cfg(feature = "async")] +fn internal_disable_interrupts() { + let sens = unsafe { &*SENS::ptr() }; + sens.sar_touch_enable() + .write(|w| unsafe { w.touch_pad_outen1().bits(0) }); + if sens.sar_touch_enable().read().touch_pad_outen1().bits() == 0 { + let rtccntl = unsafe { &*RTC_CNTL::ptr() }; + rtccntl.int_ena().write(|w| w.touch().clear_bit()); + } +} + +fn internal_clear_interrupt() { + let rtccntl = unsafe { &*RTC_CNTL::ptr() }; + rtccntl.int_clr().write(|w| w.touch().clear_bit_by_one()); + let sens = unsafe { &*SENS::ptr() }; + sens.sar_touch_ctrl2() + .write(|w| w.touch_meas_en_clr().set_bit()); +} + +fn internal_pins_touched() -> u16 { + let sens = unsafe { &*SENS::ptr() }; + // Only god knows, why the "interrupt flag" register is called "meas_en" on this + // chip... + sens.sar_touch_ctrl2().read().touch_meas_en().bits() +} + +fn internal_is_interrupt_set(touch_nr: u8) -> bool { + internal_pins_touched() & (1 << touch_nr) != 0 +} + +#[cfg(feature = "async")] +mod asynch { + use core::{ + sync::atomic::{AtomicU16, Ordering}, + task::{Context, Poll}, + }; + + use embassy_sync::waitqueue::AtomicWaker; + + use super::*; + use crate::{macros::ram, prelude::handler, Async}; + + const NUM_TOUCH_PINS: usize = 10; + + #[allow(clippy::declare_interior_mutable_const)] + const NEW_AW: AtomicWaker = AtomicWaker::new(); + static TOUCH_WAKERS: [AtomicWaker; NUM_TOUCH_PINS] = [NEW_AW; NUM_TOUCH_PINS]; + + // Helper variable to store which pins need handling. + static TOUCHED_PINS: AtomicU16 = AtomicU16::new(0); + + pub struct TouchFuture { + touch_nr: u8, + } + + impl TouchFuture { + pub fn new(touch_nr: u8) -> Self { + Self { touch_nr } + } + } + + impl core::future::Future for TouchFuture { + type Output = (); + + fn poll(self: core::pin::Pin<&mut Self>, cx: &mut Context<'_>) -> Poll { + TOUCH_WAKERS[self.touch_nr as usize].register(cx.waker()); + + let pins = TOUCHED_PINS.load(Ordering::Acquire); + + if pins & (1 << self.touch_nr) != 0 { + // clear the pin to signal that this pin was handled. + TOUCHED_PINS.fetch_and(!(1 << self.touch_nr), Ordering::Release); + Poll::Ready(()) + } else { + Poll::Pending + } + } + } + + #[handler] + #[ram] + pub(super) fn handle_touch_interrupt() { + let touch_pads = internal_pins_touched(); + for (i, waker) in TOUCH_WAKERS.iter().enumerate() { + if touch_pads & (1 << i) != 0 { + waker.wake(); + } + } + TOUCHED_PINS.store(touch_pads, Ordering::Relaxed); + internal_clear_interrupt(); + internal_disable_interrupts(); + } + + impl TouchPad { + /// Wait for the pad to be touched. + pub async fn wait_for_touch(&mut self, threshold: u16) { + self.pin.set_threshold(threshold, Internal); + let touch_nr = self.pin.get_touch_nr(Internal); + internal_enable_interrupt(touch_nr); + TouchFuture::new(touch_nr).await; + } + } +} diff --git a/esp-metadata/devices/esp32.toml b/esp-metadata/devices/esp32.toml index 53d81d9f8..e5a70a666 100644 --- a/esp-metadata/devices/esp32.toml +++ b/esp-metadata/devices/esp32.toml @@ -60,6 +60,7 @@ symbols = [ "wifi", "psram", "timg_timer1", + "touch", "large_intr_status", # ROM capabilities diff --git a/examples/src/bin/embassy_touch.rs b/examples/src/bin/embassy_touch.rs new file mode 100644 index 000000000..9d677b900 --- /dev/null +++ b/examples/src/bin/embassy_touch.rs @@ -0,0 +1,98 @@ +//! This example shows how to use the touch pad in an embassy context. +//! +//! The touch pad reading for GPIO pin 2 is manually read twice a second, +//! whereas GPIO pin 4 is configured to raise an interrupt upon touch. +//! +//! GPIO pins 2 and 4 must be connected to a touch pad (usually a larger copper +//! pad on a PCB). + +//% CHIPS: esp32 +//% FEATURES: async embassy esp-hal-embassy/integrated-timers + +#![no_std] +#![no_main] + +use embassy_executor::Spawner; +use embassy_futures::select::{select, Either}; +use embassy_time::{Duration, Timer}; +use esp_backtrace as _; +use esp_hal::{ + clock::ClockControl, + gpio::Io, + peripherals::Peripherals, + rtc_cntl::Rtc, + system::SystemControl, + timer::{timg::TimerGroup, ErasedTimer, OneShotTimer}, + touch::{Touch, TouchConfig, TouchPad}, +}; +use esp_println::println; + +// When you are okay with using a nightly compiler it's better to use https://docs.rs/static_cell/2.1.0/static_cell/macro.make_static.html +macro_rules! mk_static { + ($t:ty,$val:expr) => {{ + static STATIC_CELL: static_cell::StaticCell<$t> = static_cell::StaticCell::new(); + #[deny(unused_attributes)] + let x = STATIC_CELL.uninit().write(($val)); + x + }}; +} + +#[esp_hal_embassy::main] +async fn main(_spawner: Spawner) { + esp_println::logger::init_logger_from_env(); + + let peripherals = Peripherals::take(); + let system = SystemControl::new(peripherals.SYSTEM); + let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + + let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks); + let timer0: ErasedTimer = timg0.timer0.into(); + let timers = [OneShotTimer::new(timer0)]; + let timers = mk_static!([OneShotTimer; 1], timers); + esp_hal_embassy::init(&clocks, timers); + + 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_cfg = Some(TouchConfig { + measurement_duration: Some(0x2000), + ..Default::default() + }); + + let touch = Touch::async_mode(peripherals.TOUCH, &mut rtc, touch_cfg); + let mut touch0 = TouchPad::new(touch_pin0, &touch); + let mut touch1 = TouchPad::new(touch_pin1, &touch); + + // The touch peripheral needs some time for the first measurement + Timer::after(Duration::from_millis(100)).await; + let mut touch0_baseline = touch0.try_read(); + while touch0_baseline.is_none() { + Timer::after(Duration::from_millis(100)).await; + touch0_baseline = touch0.try_read(); + } + let touch0_baseline = touch0.try_read().unwrap(); + let touch1_baseline = touch1.try_read().unwrap(); + + println!("Waiting for touch pad interactions..."); + + loop { + match select( + touch0.wait_for_touch(touch0_baseline * 2 / 3), + touch1.wait_for_touch(touch1_baseline * 2 / 3), + ) + .await + { + Either::First(_) => { + println!("Touchpad 0 touched!"); + } + Either::Second(_) => { + println!("Touchpad 1 touched!"); + } + } + // Add some "dead-timer" to avoid command line spamming + Timer::after(Duration::from_millis(500)).await; + } +} diff --git a/examples/src/bin/touch.rs b/examples/src/bin/touch.rs new file mode 100644 index 000000000..f7870b07c --- /dev/null +++ b/examples/src/bin/touch.rs @@ -0,0 +1,98 @@ +//! This example shows how to configure a pin as a touch pad. +//! +//! The touch pad reading for GPIO pin 2 is manually read twice a second, +//! whereas GPIO pin 4 is configured to raise an interrupt upon touch. +//! +//! GPIO pins 2 and 4 must be connected to a touch pad (usually a larger copper +//! pad on a PCB). + +//% CHIPS: esp32 + +#![no_std] +#![no_main] + +use core::cell::RefCell; + +use critical_section::Mutex; +use esp_backtrace as _; +use esp_hal::{ + clock::ClockControl, + delay::Delay, + gpio, + gpio::Io, + macros::ram, + peripherals::Peripherals, + prelude::*, + rtc_cntl::Rtc, + system::SystemControl, + touch::{Continous, Touch, TouchConfig, TouchPad}, + Blocking, +}; +use esp_println::println; + +static TOUCH1: Mutex>>> = + Mutex::new(RefCell::new(None)); + +#[handler] +#[ram] +fn interrupt_handler() { + critical_section::with(|cs| { + let mut touch1 = TOUCH1.borrow_ref_mut(cs); + let touch1 = touch1.as_mut().unwrap(); + if touch1.is_interrupt_set() { + println!("touch 1 pin interrupt"); + touch1.clear_interrupt(); + // We disable the interrupt until the next loop iteration to avoid massive retriggering. + touch1.disable_interrupt(); + } + }); +} + +#[entry] +fn main() -> ! { + esp_println::logger::init_logger_from_env(); + let peripherals = Peripherals::take(); + let system = SystemControl::new(peripherals.SYSTEM); + let clocks = ClockControl::boot_defaults(system.clock_control).freeze(); + + let io = Io::new(peripherals.GPIO, peripherals.IO_MUX); + + let mut rtc = Rtc::new(peripherals.LPWR); + rtc.set_interrupt_handler(interrupt_handler); + + let touch_pin0 = io.pins.gpio2; + let touch_pin1 = io.pins.gpio4; + + let touch_cfg = Some(TouchConfig { + measurement_duration: Some(0x2000), + ..Default::default() + }); + + let touch = Touch::continous_mode(peripherals.TOUCH, touch_cfg); + let mut touch0 = TouchPad::new(touch_pin0, &touch); + let mut touch1 = TouchPad::new(touch_pin1, &touch); + + let delay = Delay::new(&clocks); + + let touch1_baseline = touch1.read(); + + critical_section::with(|cs| { + // A good threshold is 2/3 of the reading when the pad is not touched. + touch1.enable_interrupt(touch1_baseline * 2 / 3); + TOUCH1.borrow_ref_mut(cs).replace(touch1) + }); + + loop { + let touch_reading = touch0.read(); + println!("touch pad measurement: {touch_reading:?}"); + delay.delay_millis(500); + + critical_section::with(|cs| { + TOUCH1 + .borrow_ref_mut(cs) + .as_mut() + .unwrap() + .enable_interrupt(touch1_baseline * 2 / 3); + }); + } +}