Remove more examples. Update doctests. (#2547)

* WIP

* WIP(1)

* done

* changelog entry

* swint example needs to lose some weight

+ fix psram

* get twai and touch examples back, lcd example to qa, less embassy

* more moving

* move changelog entry

* address reviews

upd: revert "is_not_release" check

* rebase + a bit more changes

remove useless feature

* address review

remove inappropriate doctest tutorial

* get all sleep examples back and to qa-test

fmt

* get rid of some redundant printlns in doctests

* etm timer upd

* make printlns great again

* writeln! -> println!

* clear "timer with interrupts" doctest
This commit is contained in:
Kirill Mikhailov 2024-11-25 09:13:35 +01:00 committed by GitHub
parent 3adb0b288e
commit 8b36a43c07
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
79 changed files with 1097 additions and 2363 deletions

View File

@ -39,6 +39,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
### Fixed
### Removed
- Remove more examples. Update doctests. (#2547)
- The `configure` and `configure_for_async` DMA channel functions has been removed (#2403)
- The DMA channel objects no longer have `tx` and `rx` fields. (#2526)

View File

@ -20,7 +20,7 @@
//!
//! The ADC driver implements the `embedded-hal@0.2.x` ADC traits.
//!
//! ## Example
//! ## Examples
//!
//! ### Read an analog signal from a pin
//!

View File

@ -11,7 +11,7 @@
//! `ESP32-S2` are using older `PDMA` controller, whenever other chips are using
//! newer `GDMA` controller.
//!
//! ## Example
//! ## Examples
//!
//! ### Initialize and utilize DMA controller in `SPI`
//!

View File

@ -21,6 +21,8 @@
//! For more information, please refer to the
#![doc = concat!("[ESP-IDF documentation](https://docs.espressif.com/projects/esp-idf/en/latest/", crate::soc::chip!(), "/api-reference/peripherals/etm.html)")]
//! ## Examples
//!
//! ### Control LED by the button via ETM
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::gpio::etm::{Channels, InputConfig, OutputConfig};
@ -56,6 +58,49 @@
//! loop {}
//! # }
//! ```
//!
//! ### Control LED by the systimer via ETM
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::gpio::etm::{Channels, InputConfig, OutputConfig};
//! # use esp_hal::etm::Etm;
//! # use esp_hal::gpio::Pull;
//! # use esp_hal::gpio::Level;
//! # use esp_hal::timer::systimer::{etm::Event, SystemTimer};
//! # use esp_hal::timer::PeriodicTimer;
//! # use fugit::ExtU32;
//!
//! let syst = SystemTimer::new(peripherals.SYSTIMER);
//! let mut alarm0 = syst.alarm0;
//! let mut timer = PeriodicTimer::new(&mut alarm0);
//! timer.start(1u64.secs());
//!
//! let mut led = peripherals.GPIO1;
//!
//! // setup ETM
//! let gpio_ext = Channels::new(peripherals.GPIO_SD);
//! let led_task = gpio_ext.channel0_task.toggle(
//! &mut led,
//! OutputConfig {
//! open_drain: false,
//! pull: Pull::None,
//! initial_state: Level::Low,
//! },
//! );
//!
//! let timer_event = Event::new(&mut alarm0);
//!
//! let etm = Etm::new(peripherals.SOC_ETM);
//! let channel0 = etm.channel0;
//!
//! // make sure the configured channel doesn't get dropped - dropping it will
//! // disable the channel
//! let _configured_channel = channel0.setup(&timer_event, &led_task);
//!
//! // the LED is controlled by the timer without involving the CPU
//! loop {}
//! # }
//! ```
use crate::{
peripheral::{Peripheral, PeripheralRef},

View File

@ -14,7 +14,7 @@
//! the peripherals in LP system during chip Deep-sleep, and wake up the
//! chip from Deep-sleep.
//!
//! # Example
//! ## Examples
//!
//! ## Configure a LP Pin as Output
//!

View File

@ -16,7 +16,7 @@
//! the peripherals in RTC system during chip Deep-sleep, and wake up the
//! chip from Deep-sleep.
//!
//! ## Example
//! ## Examples
//!
//! ### Configure a ULP Pin as Output
//!

View File

@ -23,9 +23,9 @@
//! - `DMA`
//! - `system` (to configure and enable the I2S peripheral)
//!
//! ## Example
//! ## Examples
//!
//! ### Initialization
//! ### I2S Read
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]

View File

@ -34,6 +34,71 @@
//! - `GPIO`
//! - `DMA`
//! - `system` (to configure and enable the I2S peripheral)
//!
//! ## Examples
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::dma::{Dma, DmaTxBuf};
//! # use esp_hal::dma_buffers;
//! # use esp_hal::delay::Delay;
//! # use esp_hal::i2s::parallel::{I2sParallel, TxEightBits};
//! # use esp_hal::prelude::*;
//!
//! const BUFFER_SIZE: usize = 256;
//!
//! let delay = Delay::new();
//! let dma = Dma::new(peripherals.DMA);
//! let dma_channel = dma.i2s1channel;
//! let i2s = peripherals.I2S1;
//! let clock = peripherals.GPIO25;
//!
//! let pins = TxEightBits::new(
//! 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);
//! let mut parallel = I2sParallel::new(
//! i2s,
//! dma_channel,
//! 1.MHz(),
//! pins,
//! clock,
//! ).into_async();
//!
//! for (i, data) in tx_buffer.chunks_mut(4).enumerate() {
//! let offset = i * 4;
//! // i2s parallel driver expects the buffer to be interleaved
//! data[0] = (offset + 2) as u8;
//! data[1] = (offset + 3) as u8;
//! data[2] = offset as u8;
//! data[3] = (offset + 1) as u8;
//! }
//!
//! let mut tx_buf: DmaTxBuf =
//! DmaTxBuf::new(tx_descriptors, tx_buffer).expect("DmaTxBuf::new failed");
//!
//! // Sending 256 bytes.
//! loop {
//! let xfer = match parallel.send(tx_buf) {
//! Ok(xfer) => xfer,
//! Err(_) => {
//! panic!("Failed to send buffer");
//! }
//! };
//! (parallel, tx_buf) = xfer.wait();
//! delay.delay_millis(10);
//! }
//! # }
//! ```
//!
use core::{
mem::ManuallyDrop,
ops::{Deref, DerefMut},

View File

@ -24,7 +24,7 @@
//! We reserve a number of CPU interrupts, which cannot be used; see
//! [`RESERVED_INTERRUPTS`].
//!
//! ## Example
//! ## Examples
//!
//! ### Using the peripheral driver to register an interrupt handler
//!
@ -60,7 +60,7 @@
//!
//! #[handler(priority = Priority::Priority1)]
//! fn swint0_handler() {
//! // esp_println::println!("SW interrupt0");
//! println!("SW interrupt0");
//! critical_section::with(|cs| {
//! SWINT0.borrow_ref(cs).as_ref().unwrap().reset();
//! });

View File

@ -20,7 +20,7 @@
//! // Set up the interrupt handler. Do this in a critical section so the global
//! // contains the interrupt object before the interrupt is triggered.
//! critical_section::with(|cs| {
//! int0.set_interrupt_handler(interrupt_handler);
//! int0.set_interrupt_handler(swint0_handler);
//! SWINT0.borrow_ref_mut(cs).replace(int0);
//! });
//! # }
@ -35,8 +35,8 @@
//! Mutex::new(RefCell::new(None));
//!
//! #[handler]
//! fn interrupt_handler() {
//! // esp_println::println!("SW interrupt0 handled");
//! fn swint0_handler() {
//! println!("SW interrupt0 handled");
//!
//! // Clear the interrupt request.
//! critical_section::with(|cs| {

View File

@ -6,7 +6,7 @@
//! format/timing. The driver mandates DMA (Direct Memory Access) for
//! efficient data transfer.
//!
//! ## Example
//! ## Examples
//!
//! ### MIPI-DSI Display
//!

View File

@ -20,15 +20,17 @@
//! ### Low Speed Channel
//!
//! The following example will configure the Low Speed Channel0 to 24kHz output
//! with 10% duty using the ABPClock.
//! with 10% duty using the ABPClock and turn on LED with the option to change
//! LED intensity depending on `duty` value. Possible values (`u32`) are in
//! range 0..100.
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::ledc::Ledc;
//! # use esp_hal::ledc::LSGlobalClkSource;
//! # use esp_hal::ledc::timer;
//! # use esp_hal::ledc::timer::{self, TimerIFace};
//! # use esp_hal::ledc::LowSpeed;
//! # use esp_hal::ledc::channel;
//! # use esp_hal::ledc::channel::{self, ChannelIFace};
//! # let led = peripherals.GPIO0;
//!
//! let mut ledc = Ledc::new(peripherals.LEDC);
@ -51,6 +53,15 @@
//! pin_config: channel::config::PinConfig::PushPull,
//! })
//! .unwrap();
//!
//! loop {
//! // Set up a breathing LED: fade from off to on over a second, then
//! // from on back off over the next second. Then loop.
//! channel0.start_duty_fade(0, 100, 1000).unwrap();
//! while channel0.is_duty_fade_running() {}
//! channel0.start_duty_fade(100, 0, 1000).unwrap();
//! while channel0.is_duty_fade_running() {}
//! }
//! # }
//! ```
//!

View File

@ -19,6 +19,9 @@ macro_rules! before_snippet {
# macro_rules! println {
# ($($tt:tt)*) => { };
# }
# macro_rules! print {
# ($($tt:tt)*) => { };
# }
# #[panic_handler]
# fn panic(_ : &core::panic::PanicInfo) -> ! {
# loop {}

View File

@ -12,16 +12,122 @@
//!
//! ## Examples
//! ### Initialization for RX
//! See the [Parallel IO RX] example to learn how to initialize the RX and
//! reading data.
//!
//! [Parallel IO RX]: https://github.com/esp-rs/esp-hal/blob/main/examples/src/bin/parl_io_rx.rs
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::delay::Delay;
//! # use esp_hal::dma::Dma;
//! # use esp_hal::dma_buffers;
//! # use esp_hal::gpio::NoPin;
//! # use esp_hal::parl_io::{BitPackOrder, ParlIoRxOnly, RxFourBits};
//!
//! // Initialize DMA buffer and descriptors for data reception
//! let (rx_buffer, rx_descriptors, _, _) = dma_buffers!(32000, 0);
//! let dma = Dma::new(peripherals.DMA);
//! let dma_channel = dma.channel0;
//!
//! // Configure the 4-bit input pins and clock pin
//! let mut rx_pins = RxFourBits::new(
//! peripherals.GPIO1,
//! peripherals.GPIO2,
//! peripherals.GPIO3,
//! peripherals.GPIO4,
//! );
//! let mut rx_clk_pin = NoPin;
//!
//! // Set up Parallel IO for 1MHz data input, with DMA and bit packing
//! // configuration
//! let parl_io = ParlIoRxOnly::new(
//! peripherals.PARL_IO,
//! dma_channel,
//! rx_descriptors,
//! 1.MHz(),
//! )
//! .unwrap();
//!
//! let mut parl_io_rx = parl_io
//! .rx
//! .with_config(
//! &mut rx_pins,
//! &mut rx_clk_pin,
//! BitPackOrder::Msb,
//! Some(0xfff),
//! )
//! .unwrap();
//!
//! // Initialize the buffer and delay
//! let mut buffer = rx_buffer;
//! buffer.fill(0u8);
//! let delay = Delay::new();
//!
//! loop {
//! // Read data via DMA and print received values
//! let transfer = parl_io_rx.read_dma(&mut buffer).unwrap();
//! transfer.wait().unwrap();
//!
//! delay.delay_millis(500);
//! }
//! # }
//! ```
//!
//! ### Initialization for TX
//! See the [Parallel IO TX] example to learn how to initialize the TX and
//! transferring data.
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::delay::Delay;
//! # use esp_hal::dma::Dma;
//! # use esp_hal::dma_buffers;
//! # use esp_hal::parl_io::{BitPackOrder, ParlIoTxOnly, TxFourBits, SampleEdge, ClkOutPin, TxPinConfigWithValidPin};
//!
//! [Parallel IO TX]: https://github.com/esp-rs/esp-hal/blob/main/examples/src/bin/parl_io_tx.rs
//! // Initialize DMA buffer and descriptors for data reception
//! let (_, _, tx_buffer, tx_descriptors) = dma_buffers!(0, 32000);
//! let dma = Dma::new(peripherals.DMA);
//! let dma_channel = dma.channel0;
//!
//! // Configure the 4-bit input pins and clock pin
//! let tx_pins = TxFourBits::new(
//! peripherals.GPIO1,
//! peripherals.GPIO2,
//! peripherals.GPIO3,
//! peripherals.GPIO4,
//! );
//!
//! let mut pin_conf = TxPinConfigWithValidPin::new(tx_pins, peripherals.GPIO5);
//!
//! // Set up Parallel IO for 1MHz data input, with DMA and bit packing
//! // configuration
//! let parl_io = ParlIoTxOnly::new(
//! peripherals.PARL_IO,
//! dma_channel,
//! tx_descriptors,
//! 1.MHz(),
//! )
//! .unwrap();
//!
//! let mut clock_pin = ClkOutPin::new(peripherals.GPIO6);
//! let mut parl_io_tx = parl_io
//! .tx
//! .with_config(
//! &mut pin_conf,
//! &mut clock_pin,
//! 0,
//! SampleEdge::Normal,
//! BitPackOrder::Msb,
//! )
//! .unwrap();
//!
//! let buffer = tx_buffer;
//! for i in 0..buffer.len() {
//! buffer[i] = (i % 255) as u8;
//! }
//!
//! let delay = Delay::new();
//! loop {
//! let transfer = parl_io_tx.write_dma(&buffer).unwrap();
//! transfer.wait().unwrap();
//! delay.delay_millis(500);
//! }
//! # }
//! ```
use enumset::{EnumSet, EnumSetType};
use fugit::HertzU32;

View File

@ -14,11 +14,84 @@
//!
//! ## Examples
//! ### Decoding a quadrature encoder
//! Visit the [PCNT Encoder] example for an example of using the peripheral.
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::gpio::{Input, Pull};
//! # use esp_hal::interrupt::Priority;
//! # use esp_hal::pcnt::{channel, unit, Pcnt};
//! # use core::{sync::atomic::Ordering, cell::RefCell, cmp::min};
//! # use critical_section::Mutex;
//! # use portable_atomic::AtomicI32;
//!
//! static UNIT0: Mutex<RefCell<Option<unit::Unit<'static, 1>>>> =
//! Mutex::new(RefCell::new(None)); static VALUE: AtomicI32 = AtomicI32::new(0);
//!
//! // Initialize Pulse Counter (PCNT) unit with limits and filter settings
//! let mut pcnt = Pcnt::new(peripherals.PCNT);
//! pcnt.set_interrupt_handler(interrupt_handler);
//! let u0 = pcnt.unit1;
//! u0.set_low_limit(Some(-100)).unwrap();
//! u0.set_high_limit(Some(100)).unwrap();
//! u0.set_filter(Some(min(10u16 * 80, 1023u16))).unwrap();
//! u0.clear();
//!
//! // Set up channels with control and edge signals
//! let ch0 = &u0.channel0;
//! 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();
//! ch0.set_ctrl_signal(input_a.clone());
//! ch0.set_edge_signal(input_b.clone());
//! ch0.set_ctrl_mode(channel::CtrlMode::Reverse, channel::CtrlMode::Keep);
//! ch0.set_input_mode(channel::EdgeMode::Increment,
//! channel::EdgeMode::Decrement);
//!
//! let ch1 = &u0.channel1;
//! ch1.set_ctrl_signal(input_b);
//! ch1.set_edge_signal(input_a);
//! ch1.set_ctrl_mode(channel::CtrlMode::Reverse, channel::CtrlMode::Keep);
//! ch1.set_input_mode(channel::EdgeMode::Decrement,
//! channel::EdgeMode::Increment);
//!
//! // Enable interrupts and resume pulse counter unit
//! u0.listen();
//! u0.resume();
//! let counter = u0.counter.clone();
//!
//! critical_section::with(|cs| UNIT0.borrow_ref_mut(cs).replace(u0));
//!
//! // Monitor counter value and print updates
//! let mut last_value: i32 = 0;
//! loop {
//! let value: i32 = counter.get() as i32 + VALUE.load(Ordering::SeqCst);
//! if value != last_value {
//! last_value = value;
//! }
//! }
//!
//! #[handler(priority = Priority::Priority2)]
//! fn interrupt_handler() {
//! critical_section::with(|cs| {
//! let mut u0 = UNIT0.borrow_ref_mut(cs);
//! let u0 = u0.as_mut().unwrap();
//! if u0.interrupt_is_set() {
//! let events = u0.events();
//! if events.high_limit {
//! VALUE.fetch_add(100, Ordering::SeqCst);
//! } else if events.low_limit {
//! VALUE.fetch_add(-100, Ordering::SeqCst);
//! }
//! u0.reset_interrupt();
//! }
//! });
//! }
//! # }
//! ```
//!
//! [channel]: channel/index.html
//! [unit]: unit/index.html
//! [PCNT Encoder]: https://github.com/esp-rs/esp-hal/blob/main/examples/src/bin/pcnt_encoder.rs
use self::unit::Unit;
use crate::{

View File

@ -45,7 +45,7 @@
//! channels are indicated by n which is used as a placeholder for the channel
//! number, and by m for RX channels.
//!
//! ## Example
//! ## Examples
//!
//! ### Initialization
//!
@ -76,6 +76,144 @@
//! # }
//! ```
//!
//! ### TX operation
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::rmt::{PulseCode, Rmt, TxChannel, TxChannelConfig, TxChannelCreator};
//! # use esp_hal::delay::Delay;
//! # use esp_hal::prelude::*;
//!
//! // Configure frequency based on chip type
#![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 tx_config = TxChannelConfig {
//! clk_divider: 255,
//! ..TxChannelConfig::default()
//! };
//!
//! let mut channel = rmt
//! .channel0
//! .configure(peripherals.GPIO4, tx_config)
//! .unwrap();
//!
//! let delay = Delay::new();
//!
//! let mut data = [PulseCode::new(true, 200, false, 50); 20];
//! data[data.len() - 2] = PulseCode::new(true, 3000, false, 500);
//! data[data.len() - 1] = PulseCode::empty();
//!
//! loop {
//! let transaction = channel.transmit(&data).unwrap();
//! channel = transaction.wait().unwrap();
//! delay.delay_millis(500);
//! }
//! # }
//! ```
//!
//! ### RX operation
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::rmt::{PulseCode, Rmt, RxChannel, RxChannelConfig, RxChannelCreator};
//! # use esp_hal::delay::Delay;
//! # use esp_hal::prelude::*;
//! # use esp_hal::gpio::{Level, Output};
//!
//! const WIDTH: usize = 80;
//!
//! let mut out = Output::new(peripherals.GPIO5, Level::Low);
//!
//! // Configure frequency based on chip type
#![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 rx_config = RxChannelConfig {
//! clk_divider: 1,
//! idle_threshold: 10000,
//! ..RxChannelConfig::default()
//! };
#![cfg_attr(
any(esp32, esp32s2),
doc = "let mut channel = rmt.channel0.configure(peripherals.GPIO4, rx_config).unwrap();"
)]
#![cfg_attr(
esp32s3,
doc = "let mut channel = rmt.channel7.configure(peripherals.GPIO4, rx_config).unwrap();"
)]
#![cfg_attr(
not(any(esp32, esp32s2, esp32s3)),
doc = "let mut channel = rmt.channel2.configure(peripherals.GPIO4, rx_config).unwrap();"
)]
//! let delay = Delay::new();
//! let mut data: [u32; 48] = [PulseCode::empty(); 48];
//!
//! loop {
//! for x in data.iter_mut() {
//! x.reset()
//! }
//!
//! let transaction = channel.receive(&mut data).unwrap();
//!
//! // Simulate input
//! for i in 0u32..5u32 {
//! out.set_high();
//! delay.delay_micros(i * 10 + 20);
//! out.set_low();
//! delay.delay_micros(i * 20 + 20);
//! }
//!
//! match transaction.wait() {
//! Ok(channel_res) => {
//! channel = channel_res;
//! let mut total = 0usize;
//! for entry in &data[..data.len()] {
//! if entry.length1() == 0 {
//! break;
//! }
//! total += entry.length1() as usize;
//!
//! if entry.length2() == 0 {
//! break;
//! }
//! total += entry.length2() as usize;
//! }
//!
//! for entry in &data[..data.len()] {
//! if entry.length1() == 0 {
//! break;
//! }
//!
//! let count = WIDTH / (total / entry.length1() as usize);
//! let c = if entry.level1() { '-' } else { '_' };
//! for _ in 0..count + 1 {
//! print!("{}", c);
//! }
//!
//! if entry.length2() == 0 {
//! break;
//! }
//!
//! let count = WIDTH / (total / entry.length2() as usize);
//! let c = if entry.level2() { '-' } else { '_' };
//! for _ in 0..count + 1 {
//! print!("{}", c);
//! }
//! }
//!
//! println!();
//! }
//! Err((_err, channel_res)) => {
//! channel = channel_res;
//! }
//! }
//!
//! delay.delay_millis(1500);
//! }
//! # }
//! ```
//!
//! > Note: on ESP32 and ESP32-S2 you cannot specify a base frequency other than 80 MHz
use core::{

View File

@ -40,10 +40,56 @@
//! [`rand_core`]: https://crates.io/crates/rand_core
//!
//! ## Examples
//! Visit the [RNG] example for an example of using the RNG peripheral.
//!
//! [RNG]: https://github.com/esp-rs/esp-hal/blob/main/examples/src/bin/rng.rs
//! ### Basic RNG operation
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::{prelude::*, rng::Rng};
//!
//! let mut rng = Rng::new(peripherals.RNG);
//!
//! // Generate a random word (u32):
//! let rand_word = rng.random();
//!
//! // Fill a buffer with random bytes:
//! let mut buf = [0u8; 16];
//! rng.read(&mut buf);
//!
//! loop {}
//! # }
//! ```
//!
//! ### TRNG operation
/// ```rust, no_run
#[doc = crate::before_snippet!()]
/// # use esp_hal::rng::Trng;
/// # use esp_hal::peripherals::Peripherals;
/// # use esp_hal::peripherals::ADC1;
/// # use esp_hal::analog::adc::{AdcConfig, Attenuation, Adc};
///
/// let mut buf = [0u8; 16];
///
/// // ADC is not available from now
/// let mut trng = Trng::new(peripherals.RNG, &mut peripherals.ADC1);
/// trng.read(&mut buf);
/// let mut true_rand = trng.random();
/// let mut rng = trng.downgrade();
/// // ADC is available now
#[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();
/// rng.read(&mut buf);
/// true_rand = rng.random();
/// let pin_value: u16 = nb::block!(adc1.read_oneshot(&mut adc1_pin)).unwrap();
/// # }
/// ```
use core::marker::PhantomData;
use crate::{
@ -131,36 +177,6 @@ impl rand_core::RngCore for Rng {
/// methods to generate random numbers and fill buffers with random bytes.
/// Due to pulling the entropy source from the ADC, it uses the associated
/// registers, so to use TRNG we need to "occupy" the ADC peripheral.
///
/// ```rust, no_run
#[doc = crate::before_snippet!()]
/// # use esp_hal::rng::Trng;
/// # use esp_hal::peripherals::Peripherals;
/// # use esp_hal::peripherals::ADC1;
/// # use esp_hal::analog::adc::{AdcConfig, Attenuation, Adc};
///
/// let mut buf = [0u8; 16];
///
/// // ADC is not available from now
/// let mut trng = Trng::new(peripherals.RNG, &mut peripherals.ADC1);
/// trng.read(&mut buf);
/// let mut true_rand = trng.random();
/// let mut rng = trng.downgrade();
/// // ADC is available now
#[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();
/// rng.read(&mut buf);
/// true_rand = rng.random();
/// let pin_value: u16 = nb::block!(adc1.read_oneshot(&mut adc1_pin)).unwrap();
/// # }
/// ```
pub struct Trng<'d> {
/// The hardware random number generator instance.
pub rng: Rng,

View File

@ -31,13 +31,9 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::rom::md5;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # 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);
//! println!("{}", d);
//! # }
//! ```
//!
@ -45,10 +41,6 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::rom::md5;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let mut uart0 = Uart::new(peripherals.UART0, peripherals.GPIO1, peripherals.GPIO2).unwrap();
//! # let data0 = "Dummy";
//! # let data1 = "Dummy";
//! #
@ -56,7 +48,7 @@
//! ctx.consume(&data0);
//! ctx.consume(&data1);
//! let d: md5::Digest = ctx.compute();
//! writeln!(uart0, "{}", d);
//! println!("{}", d);
//! # }
//! ```
//!

View File

@ -16,12 +16,34 @@
//! * Low-Power Management
//! * Handling Watchdog Timers
//!
//! ## Example
//! ## Examples
//!
//! ### Get time in ms from the RTC Timer
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use core::cell::RefCell;
//! # use core::time::Duration;
//! # use esp_hal::{delay::Delay, prelude::*, rtc_cntl::Rtc};
//!
//! let rtc = Rtc::new(peripherals.LPWR);
//! let delay = Delay::new();
//!
//! loop {
//! // Print the current RTC time in milliseconds
//! let time_ms = rtc.current_time().and_utc().timestamp_millis();
//! delay.delay_millis(1000);
//!
//! // Set the time to half a second in the past
//! let new_time = rtc.current_time() - Duration::from_millis(500);
//! rtc.set_current_time(new_time);
//! }
//! # }
//! ```
//!
//! ### RWDT usage
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use core::cell::RefCell;
//! # use critical_section::Mutex;
//! # use esp_hal::delay::Delay;
//! # use esp_hal::rtc_cntl::Rtc;
@ -29,8 +51,8 @@
//! # use esp_hal::rtc_cntl::RwdtStage;
//! # use crate::esp_hal::InterruptConfigurable;
//! static RWDT: Mutex<RefCell<Option<Rwdt>>> = Mutex::new(RefCell::new(None));
//! let mut delay = Delay::new();
//!
//! let mut delay = Delay::new();
//! let mut rtc = Rtc::new(peripherals.LPWR);
//!
//! rtc.set_interrupt_handler(interrupt_handler);
@ -42,30 +64,49 @@
//!
//! // Where the `LP_WDT` interrupt handler is defined as:
//! # use core::cell::RefCell;
//!
//! # use critical_section::Mutex;
//! # use esp_hal::rtc_cntl::Rwdt;
//! # use esp_hal::rtc_cntl::RwdtStage;
//!
//! static RWDT: Mutex<RefCell<Option<Rwdt>>> = Mutex::new(RefCell::new(None));
//!
//! // Handle the corresponding interrupt
//! #[handler]
//! fn interrupt_handler() {
//! critical_section::with(|cs| {
//! // esp_println::println!("RWDT Interrupt");
//! println!("RWDT Interrupt");
//!
//! let mut rwdt = RWDT.borrow_ref_mut(cs);
//! let rwdt = rwdt.as_mut().unwrap();
//! rwdt.clear_interrupt();
//!
//! // esp_println::println!("Restarting in 5 seconds...");
//! println!("Restarting in 5 seconds...");
//!
//! rwdt.set_timeout(RwdtStage::Stage0, 5000u64.millis());
//! rwdt.unlisten();
//! });
//! }
//! ```
//!
//! ### Get time in ms from the RTC Timer
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use core::time::Duration;
//! # use esp_hal::{delay::Delay, prelude::*, rtc_cntl::Rtc};
//!
//! let rtc = Rtc::new(peripherals.LPWR);
//! let delay = Delay::new();
//!
//! loop {
//! // Get the current RTC time in milliseconds
//! let time_ms = rtc.current_time().and_utc().timestamp_millis();
//! delay.delay_millis(1000);
//!
//! // Set the time to half a second in the past
//! let new_time = rtc.current_time() - Duration::from_millis(500);
//! rtc.set_current_time(new_time);
//! }
//! # }
//! ```
use chrono::{DateTime, NaiveDateTime};
#[cfg(not(any(esp32c6, esp32h2)))]

View File

@ -50,6 +50,29 @@ pub enum WakeupLevel {
/// Represents a timer wake-up source, triggering an event after a specified
/// duration.
///
/// ```rust, no_run
#[doc = crate::before_snippet!()]
/// # use core::time::Duration;
/// # use esp_hal::delay::Delay;
/// # use esp_hal::prelude::*;
/// # use esp_hal::rtc_cntl::{reset_reason, sleep::TimerWakeupSource, wakeup_cause, Rtc, SocResetReason};
/// # use esp_hal::Cpu;
///
/// let delay = Delay::new();
/// let mut rtc = Rtc::new(peripherals.LPWR);
///
/// let reason =
/// reset_reason(Cpu::ProCpu).unwrap_or(SocResetReason::ChipPowerOn);
///
/// let wake_reason = wakeup_cause();
///
/// let timer = TimerWakeupSource::new(Duration::from_secs(5));
/// delay.delay_millis(100);
/// rtc.sleep_deep(&[&timer]);
///
/// # }
/// ```
#[derive(Debug, Default, Clone, Copy)]
#[cfg(any(esp32, esp32c3, esp32s3, esp32c6, esp32c2))]
pub struct TimerWakeupSource {
@ -76,6 +99,35 @@ pub enum Error {
}
/// External wake-up source (Ext0).
///
/// ```rust, no_run
#[doc = crate::before_snippet!()]
/// # use core::time::Duration;
/// # use esp_hal::delay::Delay;
/// # use esp_hal::prelude::*;
/// # use esp_hal::rtc_cntl::{reset_reason, sleep::{Ext0WakeupSource, TimerWakeupSource, WakeupLevel}, wakeup_cause, Rtc, SocResetReason};
/// # use esp_hal::Cpu;
/// # use esp_hal::gpio::{Input, Pull};
///
/// let delay = Delay::new();
/// let mut rtc = Rtc::new(peripherals.LPWR);
///
/// let pin_0 = Input::new(peripherals.GPIO4, Pull::None);
///
/// let reason =
/// reset_reason(Cpu::ProCpu).unwrap_or(SocResetReason::ChipPowerOn);
///
/// let wake_reason = wakeup_cause();
///
/// let timer = TimerWakeupSource::new(Duration::from_secs(30));
///
/// let ext0 = Ext0WakeupSource::new(pin_0, WakeupLevel::High);
///
/// delay.delay_millis(100);
/// rtc.sleep_deep(&[&timer, &ext0]);
///
/// # }
/// ```
#[cfg(any(esp32, esp32s3))]
pub struct Ext0WakeupSource<'a, P: RtcIoWakeupPinType> {
/// The pin used as the wake-up source.
@ -98,6 +150,41 @@ impl<'a, P: RtcIoWakeupPinType> Ext0WakeupSource<'a, P> {
}
/// External wake-up source (Ext1).
///
/// ```rust, no_run
#[doc = crate::before_snippet!()]
/// # use core::time::Duration;
/// # use esp_hal::delay::Delay;
/// # use esp_hal::prelude::*;
/// # use esp_hal::rtc_cntl::{reset_reason, sleep::{Ext1WakeupSource, TimerWakeupSource, WakeupLevel}, wakeup_cause, Rtc, SocResetReason};
/// # use esp_hal::Cpu;
/// # use esp_hal::gpio::{Input, Pull, RtcPin};
/// # use esp_hal::peripheral::Peripheral;
///
/// let delay = Delay::new();
/// let mut rtc = Rtc::new(peripherals.LPWR);
///
/// let pin_4 = Input::new(peripherals.GPIO4, Pull::None);
/// let mut pin_2 = peripherals.GPIO2;
///
/// let reason =
/// reset_reason(Cpu::ProCpu).unwrap_or(SocResetReason::ChipPowerOn);
///
/// let wake_reason = wakeup_cause();
///
/// let timer = TimerWakeupSource::new(Duration::from_secs(30));
///
///
/// let mut wakeup_pins: [&mut dyn RtcPin; 2] =
/// [&mut *pin_4.into_ref(), &mut pin_2];
///
/// let ext1 = Ext1WakeupSource::new(&mut wakeup_pins, WakeupLevel::High);
///
/// delay.delay_millis(100);
/// rtc.sleep_deep(&[&timer, &ext1]);
///
/// # }
/// ```
#[cfg(any(esp32, esp32s3))]
pub struct Ext1WakeupSource<'a, 'b> {
/// A collection of pins used as wake-up sources.
@ -119,6 +206,41 @@ impl<'a, 'b> Ext1WakeupSource<'a, 'b> {
}
/// External wake-up source (Ext1).
/// ```rust, no_run
#[doc = crate::before_snippet!()]
/// # use core::time::Duration;
/// # use esp_hal::delay::Delay;
/// # use esp_hal::prelude::*;
/// # use esp_hal::rtc_cntl::{reset_reason, sleep::{Ext1WakeupSource, TimerWakeupSource, WakeupLevel}, wakeup_cause, Rtc, SocResetReason};
/// # use esp_hal::Cpu;
/// # use esp_hal::gpio::{Input, Pull, RtcPinWithResistors};
/// # use esp_hal::peripheral::Peripheral;
///
/// let delay = Delay::new();
/// let mut rtc = Rtc::new(peripherals.LPWR);
///
/// let pin2 = Input::new(peripherals.GPIO2, Pull::None);
/// let mut pin3 = peripherals.GPIO3;
///
/// let reason =
/// reset_reason(Cpu::ProCpu).unwrap_or(SocResetReason::ChipPowerOn);
///
/// let wake_reason = wakeup_cause();
///
/// let timer = TimerWakeupSource::new(Duration::from_secs(30));
///
/// let wakeup_pins: &mut [(&mut dyn RtcPinWithResistors, WakeupLevel)] =
/// &mut [(&mut *pin2.into_ref(), WakeupLevel::Low),
/// (&mut pin3, WakeupLevel::High),
/// ];
///
/// let ext1 = Ext1WakeupSource::new(wakeup_pins);
///
/// delay.delay_millis(100);
/// rtc.sleep_deep(&[&timer, &ext1]);
///
/// # }
/// ```
#[cfg(esp32c6)]
pub struct Ext1WakeupSource<'a, 'b> {
pins: RefCell<&'a mut [(&'b mut dyn RtcIoWakeupPinType, WakeupLevel)]>,
@ -140,6 +262,54 @@ impl<'a, 'b> Ext1WakeupSource<'a, 'b> {
/// RTC_IO wakeup allows configuring any combination of RTC_IO pins with
/// arbitrary wakeup levels to wake up the chip from sleep. This wakeup source
/// can be used to wake up from both light and deep sleep.
///
/// ```rust, no_run
#[doc = crate::before_snippet!()]
/// # use core::time::Duration;
/// # use esp_hal::delay::Delay;
/// # use esp_hal::gpio::{self, Input, Pull};
/// # use esp_hal::prelude::*;
/// # use esp_hal::rtc_cntl::{reset_reason, sleep::{RtcioWakeupSource, TimerWakeupSource, WakeupLevel}, wakeup_cause, Rtc, SocResetReason};
/// # use esp_hal::Cpu;
/// # use esp_hal::peripheral::Peripheral;
///
/// let mut rtc = Rtc::new(peripherals.LPWR);
///
/// let reason =
/// reset_reason(Cpu::ProCpu).unwrap_or(SocResetReason::ChipPowerOn);
///
/// let wake_reason = wakeup_cause();
///
/// let delay = Delay::new();
/// let timer = TimerWakeupSource::new(Duration::from_secs(10));
#[cfg_attr(
any(esp32c3, esp32c2),
doc = "let pin_0 = Input::new(peripherals.GPIO2, Pull::None);"
)]
#[cfg_attr(any(esp32c3, esp32c2), doc = "let mut pin_1 = peripherals.GPIO3;")]
#[cfg_attr(
esp32s3,
doc = "let pin_0 = Input::new(peripherals.GPIO17, Pull::None);"
)]
#[cfg_attr(esp32s3, doc = "let mut pin_1 = peripherals.GPIO18;")]
#[cfg_attr(
any(esp32c3, esp32c2),
doc = "let wakeup_pins: &mut [(&mut dyn gpio::RtcPinWithResistors, WakeupLevel)] = &mut ["
)]
#[cfg_attr(
esp32s3,
doc = "let wakeup_pins: &mut [(&mut dyn gpio::RtcPin, WakeupLevel)] = &mut ["
)]
/// (&mut *pin_0.into_ref(), WakeupLevel::Low),
/// (&mut pin_1, WakeupLevel::High),
/// ];
///
/// let rtcio = RtcioWakeupSource::new(wakeup_pins);
/// delay.delay_millis(100);
/// rtc.sleep_deep(&[&timer, &rtcio]);
///
/// # }
/// ```
#[cfg(any(esp32c3, esp32s3, esp32c2))]
pub struct RtcioWakeupSource<'a, 'b> {
pins: RefCell<&'a mut [(&'b mut dyn RtcIoWakeupPinType, WakeupLevel)]>,

View File

@ -17,20 +17,17 @@
//! The `Efuse` struct represents the eFuse peripheral and is responsible for
//! reading various eFuse fields and values.
//!
//! ## Example
//! ## Examples
//!
//! ### Read chip's MAC address from the eFuse storage.
//! ### Read data from the eFuse storage.
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::efuse::Efuse;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.GPIO4, peripherals.GPIO5).unwrap();
//!
//! let mac_address = Efuse::read_base_mac_address();
//! writeln!(
//! serial_tx,
//!
//! println!(
//! "MAC: {:#X}:{:#X}:{:#X}:{:#X}:{:#X}:{:#X}",
//! mac_address[0],
//! mac_address[1],
@ -39,6 +36,13 @@
//! mac_address[4],
//! mac_address[5]
//! );
//!
//! println!("MAC address {:02x?}", Efuse::mac_address());
//! println!("Flash Encryption {:?}", Efuse::flash_encryption());
//! println!("Core Count {}", Efuse::core_count());
//! println!("Bluetooth enabled {}", Efuse::is_bluetooth_enabled());
//! println!("Chip type {:?}", Efuse::chip_type());
//! println!("Max CPU clock {:?}", Efuse::max_cpu_frequency());
//! # }
//! ```

View File

@ -9,6 +9,47 @@
//! present on the `ESP32` chip. `PSRAM` provides additional external memory to
//! supplement the internal memory of the `ESP32`, allowing for increased
//! storage capacity and improved performance in certain applications.
//!
//! ## Examples
//!
//! ### Quad PSRAM
//! This example shows how to use PSRAM as heap-memory via esp-alloc.
//! You need an ESP32 with at least 2 MB of PSRAM memory.
//! Notice that PSRAM example **must** be built in release mode!
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # extern crate alloc;
//! # use alloc::{string::String, vec::Vec};
//! # use esp_alloc as _;
//! # use esp_hal::{psram, prelude::*};
//!
//! // Initialize PSRAM and add it as a heap memory region
//! fn init_psram_heap(start: *mut u8, size: usize) {
//! unsafe {
//! esp_alloc::HEAP.add_region(esp_alloc::HeapRegion::new(
//! start,
//! size,
//! esp_alloc::MemoryCapability::External.into(),
//! ));
//! }
//! }
//!
//! // Initialize PSRAM and add it to the heap
//! let (start, size) = psram::init_psram(peripherals.PSRAM,
//! psram::PsramConfig::default());
//!
//! init_psram_heap(start, size);
//!
//! let mut large_vec: Vec<u32> = Vec::with_capacity(500 * 1024 / 4);
//!
//! for i in 0..(500 * 1024 / 4) {
//! large_vec.push((i & 0xff) as u32);
//! }
//!
//! let string = String::from("A string allocated in PSRAM");
//! # }
//! ```
pub use crate::soc::psram_common::*;

View File

@ -14,20 +14,17 @@
//! The `Efuse` struct represents the eFuse peripheral and is responsible for
//! reading various eFuse fields and values.
//!
//! ## Example
//! ## Examples
//!
//! ### Read chip's MAC address from the eFuse storage.
//! ### Read data from the eFuse storage.
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::efuse::Efuse;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.GPIO4, peripherals.GPIO5).unwrap();
//!
//! let mac_address = Efuse::read_base_mac_address();
//! writeln!(
//! serial_tx,
//!
//! println!(
//! "MAC: {:#X}:{:#X}:{:#X}:{:#X}:{:#X}:{:#X}",
//! mac_address[0],
//! mac_address[1],
@ -36,6 +33,9 @@
//! mac_address[4],
//! mac_address[5]
//! );
//!
//! println!("MAC address {:02x?}", Efuse::mac_address());
//! println!("Flash Encryption {:?}", Efuse::flash_encryption());
//! # }
//! ```

View File

@ -15,20 +15,17 @@
//! The `Efuse` struct represents the eFuse peripheral and is responsible for
//! reading various eFuse fields and values.
//!
//! ## Example
//! ## Examples
//!
//! ### Read chip's MAC address from the eFuse storage.
//! ### Read data from the eFuse storage.
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::efuse::Efuse;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.GPIO4, peripherals.GPIO5).unwrap();
//!
//! let mac_address = Efuse::read_base_mac_address();
//! writeln!(
//! serial_tx,
//!
//! println!(
//! "MAC: {:#X}:{:#X}:{:#X}:{:#X}:{:#X}:{:#X}",
//! mac_address[0],
//! mac_address[1],
@ -37,6 +34,9 @@
//! mac_address[4],
//! mac_address[5]
//! );
//!
//! println!("MAC address {:02x?}", Efuse::mac_address());
//! println!("Flash Encryption {:?}", Efuse::flash_encryption());
//! # }
//! ```

View File

@ -15,20 +15,17 @@
//! The `Efuse` struct represents the eFuse peripheral and is responsible for
//! reading various eFuse fields and values.
//!
//! ## Example
//! ## Examples
//!
//! ### Read chip's MAC address from the eFuse storage.
//! ### Read data from the eFuse storage.
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::efuse::Efuse;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.GPIO4, peripherals.GPIO5).unwrap();
//!
//! let mac_address = Efuse::read_base_mac_address();
//! writeln!(
//! serial_tx,
//!
//! println!(
//! "MAC: {:#X}:{:#X}:{:#X}:{:#X}:{:#X}:{:#X}",
//! mac_address[0],
//! mac_address[1],
@ -37,6 +34,9 @@
//! mac_address[4],
//! mac_address[5]
//! );
//!
//! println!("MAC address {:02x?}", Efuse::mac_address());
//! println!("Flash Encryption {:?}", Efuse::flash_encryption());
//! # }
//! ```

View File

@ -15,20 +15,17 @@
//! The `Efuse` struct represents the eFuse peripheral and is responsible for
//! reading various eFuse fields and values.
//!
//! ## Example
//! ## Examples
//!
//! ### Read chip's MAC address from the eFuse storage.
//! ### Read data from the eFuse storage.
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::efuse::Efuse;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.GPIO4, peripherals.GPIO5).unwrap();
//!
//! let mac_address = Efuse::read_base_mac_address();
//! writeln!(
//! serial_tx,
//!
//! println!(
//! "MAC: {:#X}:{:#X}:{:#X}:{:#X}:{:#X}:{:#X}",
//! mac_address[0],
//! mac_address[1],
@ -37,6 +34,9 @@
//! mac_address[4],
//! mac_address[5]
//! );
//!
//! println!("MAC address {:02x?}", Efuse::mac_address());
//! println!("Flash Encryption {:?}", Efuse::flash_encryption());
//! # }
//! ```

View File

@ -17,20 +17,17 @@
//! The `Efuse` struct represents the eFuse peripheral and is responsible for
//! reading various eFuse fields and values.
//!
//! ## Example
//! ## Examples
//!
//! ### Read chip's MAC address from the eFuse storage.
//! ### Read data from the eFuse storage.
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::efuse::Efuse;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.GPIO4, peripherals.GPIO5).unwrap();
//!
//! let mac_address = Efuse::read_base_mac_address();
//! writeln!(
//! serial_tx,
//!
//! println!(
//! "MAC: {:#X}:{:#X}:{:#X}:{:#X}:{:#X}:{:#X}",
//! mac_address[0],
//! mac_address[1],
@ -39,6 +36,9 @@
//! mac_address[4],
//! mac_address[5]
//! );
//!
//! println!("MAC address {:02x?}", Efuse::mac_address());
//! println!("Flash Encryption {:?}", Efuse::flash_encryption());
//! # }
//! ```

View File

@ -9,6 +9,47 @@
//! present on the `ESP32-S2` chip. `PSRAM` provides additional external memory
//! to supplement the internal memory of the `ESP32-S2`, allowing for increased
//! storage capacity and improved performance in certain applications.
//!
//! //! ## Examples
//!
//! ### Quad PSRAM
//! This example shows how to use PSRAM as heap-memory via esp-alloc.
//! You need an ESP32S2 with at least 2 MB of PSRAM memory.
//! Notice that PSRAM example **must** be built in release mode!
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # extern crate alloc;
//! # use alloc::{string::String, vec::Vec};
//! # use esp_alloc as _;
//! # use esp_hal::{psram, prelude::*};
//!
//! // Initialize PSRAM and add it as a heap memory region
//! fn init_psram_heap(start: *mut u8, size: usize) {
//! unsafe {
//! esp_alloc::HEAP.add_region(esp_alloc::HeapRegion::new(
//! start,
//! size,
//! esp_alloc::MemoryCapability::External.into(),
//! ));
//! }
//! }
//!
//! // Initialize PSRAM and add it to the heap
//! let (start, size) = psram::init_psram(peripherals.PSRAM,
//! psram::PsramConfig::default());
//!
//! init_psram_heap(start, size);
//!
//! let mut large_vec: Vec<u32> = Vec::with_capacity(500 * 1024 / 4);
//!
//! for i in 0..(500 * 1024 / 4) {
//! large_vec.push((i & 0xff) as u32);
//! }
//!
//! let string = String::from("A string allocated in PSRAM");
//! # }
//! ```
pub use crate::soc::psram_common::*;

View File

@ -15,20 +15,17 @@
//! The `Efuse` struct represents the eFuse peripheral and is responsible for
//! reading various eFuse fields and values.
//!
//! ## Example
//! ## Examples
//!
//! ### Read chip's MAC address from the eFuse storage.
//! ### Read data from the eFuse storage.
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::efuse::Efuse;
//! # use esp_hal::uart::Uart;
//! # use core::writeln;
//! # use core::fmt::Write;
//! # let mut serial_tx = Uart::new(peripherals.UART0, peripherals.GPIO4, peripherals.GPIO5).unwrap();
//!
//! let mac_address = Efuse::read_base_mac_address();
//! writeln!(
//! serial_tx,
//!
//! println!(
//! "MAC: {:#X}:{:#X}:{:#X}:{:#X}:{:#X}:{:#X}",
//! mac_address[0],
//! mac_address[1],
@ -37,6 +34,9 @@
//! mac_address[4],
//! mac_address[5]
//! );
//!
//! println!("MAC address {:02x?}", Efuse::mac_address());
//! println!("Flash Encryption {:?}", Efuse::flash_encryption());
//! # }
//! ```

View File

@ -12,6 +12,49 @@
//!
//! The mapped start address for PSRAM depends on the amount of mapped flash
//! memory.
//!
//! ## Examples
//!
//! ### Octal/Quad PSRAM
//! This example shows how to use PSRAM as heap-memory via esp-alloc.
//! You need an ESP32-S3 with at least 2 MB of PSRAM memory.
//! Either `Octal` or `Quad` PSRAM will be used, depending on whether
//! `octal-psram` or `quad-psram` feature is enabled.
//! Notice that PSRAM example **must** be built in release mode!
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # extern crate alloc;
//! # use alloc::{string::String, vec::Vec};
//! # use esp_alloc as _;
//! # use esp_hal::{psram, prelude::*};
//!
//! // Initialize PSRAM and add it as a heap memory region
//! fn init_psram_heap(start: *mut u8, size: usize) {
//! unsafe {
//! esp_alloc::HEAP.add_region(esp_alloc::HeapRegion::new(
//! start,
//! size,
//! esp_alloc::MemoryCapability::External.into(),
//! ));
//! }
//! }
//!
//! // Initialize PSRAM and add it to the heap
//! let (start, size) = psram::init_psram(peripherals.PSRAM,
//! psram::PsramConfig::default());
//!
//! init_psram_heap(start, size);
//!
//! let mut large_vec: Vec<u32> = Vec::with_capacity(500 * 1024 / 4);
//!
//! for i in 0..(500 * 1024 / 4) {
//! large_vec.push((i & 0xff) as u32);
//! }
//!
//! let string = String::from("A string allocated in PSRAM");
//! # }
//! ```
pub use crate::soc::psram_common::*;

View File

@ -12,7 +12,7 @@
//! operation. The `UlpCore` struct is initialized with a peripheral reference
//! to the `ULP CORE` instance.
//!
//! ## Example
//! ## Examples
//!
//! ```rust, no_run
#![doc = crate::before_snippet!()]

View File

@ -33,7 +33,7 @@
//! The module implements several third-party traits from embedded-hal@0.2.x,
//! embedded-hal@1.x.x and embassy-embedded-hal
//!
//! ## Example
//! ## Examples
//!
//! ### SPI Initialization
//! ```rust, no_run

View File

@ -9,7 +9,7 @@
//!
//! The SPI slave driver allows using full-duplex and can only be used with DMA.
//!
//! ## Example
//! ## Examples
//!
//! ### SPI Slave with DMA
//!

View File

@ -63,7 +63,6 @@
//! }
//! # }
//! ```
use core::marker::PhantomData;
use fugit::{HertzU32, Instant, MicrosDurationU64};

View File

@ -36,38 +36,38 @@
//! # use nb::block;
//! // Use GPIO pins 2 and 3 to connect to the respective pins on the TWAI
//! // transceiver.
//! let can_rx_pin = peripherals.GPIO3;
//! let can_tx_pin = peripherals.GPIO2;
//! let twai_rx_pin = peripherals.GPIO3;
//! let twai_tx_pin = peripherals.GPIO2;
//!
//! // The speed of the TWAI bus.
//! const TWAI_BAUDRATE: twai::BaudRate = BaudRate::B1000K;
//!
//! // Begin configuring the TWAI peripheral. The peripheral is in a reset like
//! // state that prevents transmission but allows configuration.
//! let mut can_config = twai::TwaiConfiguration::new(
//! let mut twai_config = twai::TwaiConfiguration::new(
//! peripherals.TWAI0,
//! can_rx_pin,
//! can_tx_pin,
//! twai_rx_pin,
//! twai_tx_pin,
//! TWAI_BAUDRATE,
//! TwaiMode::Normal
//! );
//!
//! // Partially filter the incoming messages to reduce overhead of receiving
//! // undesired messages
//! can_config.set_filter(const { SingleStandardFilter::new(b"xxxxxxxxxx0",
//! twai_config.set_filter(const { SingleStandardFilter::new(b"xxxxxxxxxx0",
//! b"x", [b"xxxxxxxx", b"xxxxxxxx"]) });
//!
//! // Start the peripheral. This locks the configuration settings of the
//! // peripheral and puts it into operation mode, allowing packets to be sent
//! // and received.
//! let mut can = can_config.start();
//! let mut twai = twai_config.start();
//!
//! loop {
//! // Wait for a frame to be received.
//! let frame = block!(can.receive()).unwrap();
//! let frame = block!(twai.receive()).unwrap();
//!
//! // Transmit the frame back.
//! let _result = block!(can.transmit(&frame)).unwrap();
//! let _result = block!(twai.transmit(&frame)).unwrap();
//! }
//! # }
//! ```

View File

@ -108,6 +108,107 @@
//! # }
//! ```
//!
//! ### Operation with interrupts that by UART/Serial
//! Notice, that in practice a proper serial terminal should be used
//! to connect to the board (espmonitor and espflash won't work)
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::delay::Delay;
//! # use esp_hal::uart::{AtCmdConfig, Config, Uart, UartInterrupt};
//! # use esp_hal::prelude::*;
//! let delay = Delay::new();
//!
//! // Default pins for UART/Serial communication
#![cfg_attr(
esp32,
doc = "let (tx_pin, rx_pin) = (peripherals.GPIO1, peripherals.GPIO3);"
)]
#![cfg_attr(
esp32c2,
doc = "let (tx_pin, rx_pin) = (peripherals.GPIO20, peripherals.GPIO19);"
)]
#![cfg_attr(
esp32c3,
doc = "let (tx_pin, rx_pin) = (peripherals.GPIO21, peripherals.GPIO20);"
)]
#![cfg_attr(
esp32c6,
doc = "let (tx_pin, rx_pin) = (peripherals.GPIO16, peripherals.GPIO17);"
)]
#![cfg_attr(
esp32h2,
doc = "let (tx_pin, rx_pin) = (peripherals.GPIO24, peripherals.GPIO23);"
)]
#![cfg_attr(
any(esp32s2, esp32s3),
doc = "let (tx_pin, rx_pin) = (peripherals.GPIO43, peripherals.GPIO44);"
)]
//! let config = Config::default().rx_fifo_full_threshold(30);
//!
//! let mut uart0 = Uart::new_with_config(
//! peripherals.UART0,
//! config,
//! tx_pin,
//! rx_pin
//! ).unwrap();
//!
//! uart0.set_interrupt_handler(interrupt_handler);
//!
//! critical_section::with(|cs| {
//! uart0.set_at_cmd(AtCmdConfig::new(None, None, None, b'#', None));
//! uart0.listen(UartInterrupt::AtCmd | UartInterrupt::RxFifoFull);
//!
//! SERIAL.borrow_ref_mut(cs).replace(uart0);
//! });
//!
//! loop {
//! critical_section::with(|cs| {
//! let mut serial = SERIAL.borrow_ref_mut(cs);
//! let serial = serial.as_mut().unwrap();
//! writeln!(serial,
//! "Hello World! Send a single `#` character or send
//! at least 30 characters to trigger interrupts.")
//! .ok();
//! });
//! delay.delay(1.secs());
//! }
//! # }
//!
//! # use core::cell::RefCell;
//! # use critical_section::Mutex;
//! # use esp_hal::uart::Uart;
//! static SERIAL: Mutex<RefCell<Option<Uart<esp_hal::Blocking>>>> =
//! Mutex::new(RefCell::new(None));
//!
//! # use esp_hal::uart::UartInterrupt;
//! # use core::fmt::Write;
//! #[handler]
//! fn interrupt_handler() {
//! critical_section::with(|cs| {
//! let mut serial = SERIAL.borrow_ref_mut(cs);
//! let serial = serial.as_mut().unwrap();
//!
//! let mut cnt = 0;
//! while let nb::Result::Ok(_c) = serial.read_byte() {
//! cnt += 1;
//! }
//! writeln!(serial, "Read {} bytes", cnt).ok();
//!
//! let pending_interrupts = serial.interrupts();
//! writeln!(
//! serial,
//! "Interrupt AT-CMD: {} RX-FIFO-FULL: {}",
//! pending_interrupts.contains(UartInterrupt::AtCmd),
//! pending_interrupts.contains(UartInterrupt::RxFifoFull),
//! ).ok();
//!
//! serial.clear_interrupts(
//! UartInterrupt::AtCmd | UartInterrupt::RxFifoFull
//! );
//! });
//! }
//! ```
//!
//! [embedded-hal]: https://docs.rs/embedded-hal/latest/embedded_hal/
//! [embedded-io]: https://docs.rs/embedded-io/latest/embedded_io/
//! [embedded-hal-async]: https://docs.rs/embedded-hal-async/latest/embedded_hal_async/

View File

@ -70,6 +70,57 @@
//! # }
//! ```
//!
//! ### How to output text using USB Serial/JTAG.
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::{delay::Delay, prelude::*, usb_serial_jtag::UsbSerialJtag, Blocking};
//!
//! let delay = Delay::new();
//!
//! let mut usb_serial = UsbSerialJtag::new(peripherals.USB_DEVICE);
//! usb_serial.set_interrupt_handler(usb_device);
//! usb_serial.listen_rx_packet_recv_interrupt();
//!
//! critical_section::with(|cs|
//! USB_SERIAL.borrow_ref_mut(cs).replace(usb_serial));
//!
//! loop {
//! critical_section::with(|cs| {
//! writeln!(
//! USB_SERIAL.borrow_ref_mut(cs).as_mut().unwrap(),
//! "Hello world!"
//! )
//! .ok();
//! });
//!
//! delay.delay(1.secs());
//! }
//! # }
//!
//! # use critical_section::Mutex;
//! # use core::{cell::RefCell, fmt::Write};
//! # use esp_hal::usb_serial_jtag::UsbSerialJtag;
//! static USB_SERIAL:
//! Mutex<RefCell<Option<UsbSerialJtag<'static, esp_hal::Blocking>>>> =
//! Mutex::new(RefCell::new(None));
//!
//! #[handler]
//! fn usb_device() {
//! critical_section::with(|cs| {
//! let mut usb_serial = USB_SERIAL.borrow_ref_mut(cs);
//! let usb_serial = usb_serial.as_mut().unwrap();
//!
//! writeln!(usb_serial, "USB serial interrupt").unwrap();
//!
//! while let nb::Result::Ok(c) = usb_serial.read_byte() {
//! writeln!(usb_serial, "Read byte: {:02x}", c).unwrap();
//! }
//!
//! usb_serial.reset_rx_packet_recv_interrupt();
//! });
//! }
//! ```
//!
//! [embedded-hal]: https://docs.rs/embedded-hal/latest/embedded_hal/
//! [embedded-io]: https://docs.rs/embedded-io/latest/embedded_io/
//! [embedded-hal-async]: https://docs.rs/embedded-hal-async/latest/embedded_hal_async/

View File

@ -1,40 +0,0 @@
//! This shows how to configure UART
//! You can short the TX and RX pin and see it reads what was written.
//! Additionally you can connect a logic analyzer to TX and see how the changes
//! of the configuration change the output signal.
//!
//! The following wiring is assumed:
//! - TX => GPIO4
//! - RX => GPIO5
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{delay::Delay, prelude::*, uart::Uart};
use esp_println::println;
use nb::block;
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let mut serial1 = Uart::new(peripherals.UART1, peripherals.GPIO4, peripherals.GPIO5).unwrap();
let delay = Delay::new();
println!("Start");
loop {
serial1.write_byte(0x42).ok();
let read = block!(serial1.read_byte());
match read {
Ok(read) => println!("Read 0x{:02x}", read),
Err(err) => println!("Error {:?}", err),
}
delay.delay_millis(250);
}
}

View File

@ -1,56 +0,0 @@
//! Blinks 3 LEDs
//!
//! The boot button is treated as an input, and will print a message when pressed.
//! This additionally demonstrates passing GPIO to a function in a generic way.
//!
//! The following wiring is assumed:
//! - LEDs => GPIO2, GPIO4, GPIO5
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{
delay::Delay,
gpio::{Input, Level, Output, Pin, Pull},
prelude::*,
};
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
// Set LED GPIOs as an output:
let led1 = Output::new(peripherals.GPIO2.degrade(), Level::Low);
let led2 = Output::new(peripherals.GPIO4.degrade(), Level::Low);
let led3 = Output::new(peripherals.GPIO5.degrade(), Level::Low);
// Use boot button as an input:
#[cfg(any(feature = "esp32", feature = "esp32s2", feature = "esp32s3"))]
let button = peripherals.GPIO0.degrade();
#[cfg(not(any(feature = "esp32", feature = "esp32s2", feature = "esp32s3")))]
let button = peripherals.GPIO9.degrade();
let button = Input::new(button, Pull::Up);
let mut pins = [led1, led2, led3];
let delay = Delay::new();
loop {
toggle_pins(&mut pins, &button);
delay.delay_millis(500);
}
}
fn toggle_pins(leds: &mut [Output], button: &Input) {
for pin in leds.iter_mut() {
pin.toggle();
}
if button.is_low() {
esp_println::println!("Button pressed");
}
}

View File

@ -1,84 +0,0 @@
//! This shows using Parallel IO to output 8 bit parallel data at 1MHz clock
//! rate with a delay of 10ms between each transfer.
//!
//! The following wiring is assumed:
//! - Data pins => GPIO16, GPIO4, GPIO17, GPIO18, GPIO5, GPIO19, GPIO12, and
//! GPIO14
//! - Clock output pin => GPIO25
//!
//! You can use a logic analyzer to see how the pins are used.
//% CHIPS: esp32
//% FEATURES: embassy embassy-generic-timers
#![no_std]
#![no_main]
use embassy_executor::Spawner;
use embassy_time::Timer;
use esp_backtrace as _;
use esp_hal::{
dma::{Dma, DmaTxBuf},
dma_buffers,
i2s::parallel::{I2sParallel, TxEightBits},
prelude::*,
timer::timg::TimerGroup,
};
use log::info;
const BUFFER_SIZE: usize = 256;
#[main]
async fn main(_spawner: Spawner) {
esp_println::logger::init_logger(log::LevelFilter::Info);
info!("Starting!");
let peripherals = esp_hal::init(esp_hal::Config::default());
let dma = Dma::new(peripherals.DMA);
let timg0 = TimerGroup::new(peripherals.TIMG0);
info!("init embassy");
esp_hal_embassy::init(timg0.timer0);
let dma_channel = dma.i2s1channel;
let i2s = peripherals.I2S1;
let clock = peripherals.GPIO25;
let pins = TxEightBits::new(
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);
let mut parallel = I2sParallel::new(i2s, dma_channel, 1.MHz(), pins, clock).into_async();
for (i, data) in tx_buffer.chunks_mut(4).enumerate() {
let offset = i * 4;
// i2s parallel driver expects the buffer to be interleaved
data[0] = (offset + 2) as u8;
data[1] = (offset + 3) as u8;
data[2] = offset as u8;
data[3] = (offset + 1) as u8;
}
let mut tx_buf = DmaTxBuf::new(tx_descriptors, tx_buffer).expect("DmaTxBuf::new failed");
info!("Sending {} bytes!", BUFFER_SIZE);
loop {
let mut xfer = match parallel.send(tx_buf) {
Ok(xfer) => xfer,
Err(_) => {
panic!("Failed to send buffer");
}
};
xfer.wait_for_done().await.expect("Failed to send buffer");
(parallel, tx_buf) = xfer.wait();
Timer::after_millis(10).await;
}
}

View File

@ -1,71 +0,0 @@
//! This shows using Parallel IO to input 4 bit parallel data at 1MHz clock
//! rate.
//!
//! The following wiring is assumed:
//! - Data pins => GPIO1, GPIO2, GPIO3, and GPIO4.
//% CHIPS: esp32c6 esp32h2
//% FEATURES: embassy embassy-generic-timers
#![no_std]
#![no_main]
use embassy_executor::Spawner;
use embassy_time::{Duration, Timer};
use esp_backtrace as _;
use esp_hal::{
dma::Dma,
dma_buffers,
gpio::NoPin,
parl_io::{BitPackOrder, ParlIoRxOnly, RxFourBits},
prelude::*,
timer::systimer::SystemTimer,
};
use esp_println::println;
#[esp_hal_embassy::main]
async fn main(_spawner: Spawner) {
esp_println::println!("Init!");
let peripherals = esp_hal::init(esp_hal::Config::default());
let systimer = SystemTimer::new(peripherals.SYSTIMER);
esp_hal_embassy::init(systimer.alarm0);
let (rx_buffer, rx_descriptors, _, _) = dma_buffers!(32000, 0);
let dma = Dma::new(peripherals.DMA);
let mut rx_pins = RxFourBits::new(
peripherals.GPIO1,
peripherals.GPIO2,
peripherals.GPIO3,
peripherals.GPIO4,
);
let mut rx_clk_pin = NoPin;
let parl_io = ParlIoRxOnly::new(peripherals.PARL_IO, dma.channel0, rx_descriptors, 1.MHz())
.unwrap()
.into_async();
let mut parl_io_rx = parl_io
.rx
.with_config(
&mut rx_pins,
&mut rx_clk_pin,
BitPackOrder::Msb,
Some(0xfff),
)
.unwrap();
let buffer = rx_buffer;
loop {
parl_io_rx.read_dma_async(buffer).await.unwrap();
println!(
"Received: {:02x?} ... {:02x?}",
&buffer[..30],
&buffer[(buffer.len() - 30)..]
);
Timer::after(Duration::from_millis(500)).await;
}
}

View File

@ -1,85 +0,0 @@
//! This shows using Parallel IO to output 4 bit parallel data at 1MHz clock
//! rate.
//!
//! The following wiring is assumed:
//! - Data pins => GPIO1, GPIO2, GPIO3, and GPIO4
//! - Valid pin => GPIO5 (driven high during an active transfer)
//! - Clock output pin => GPIO8
//!
//! You can use a logic analyzer to see how the pins are used.
//% CHIPS: esp32c6 esp32h2
//% FEATURES: embassy embassy-generic-timers
#![no_std]
#![no_main]
use embassy_executor::Spawner;
use embassy_time::{Duration, Timer};
use esp_backtrace as _;
use esp_hal::{
dma::Dma,
dma_buffers,
parl_io::{
BitPackOrder,
ClkOutPin,
ParlIoTxOnly,
SampleEdge,
TxFourBits,
TxPinConfigWithValidPin,
},
prelude::*,
timer::systimer::SystemTimer,
};
use esp_println::println;
#[esp_hal_embassy::main]
async fn main(_spawner: Spawner) {
esp_println::println!("Init!");
let peripherals = esp_hal::init(esp_hal::Config::default());
let systimer = SystemTimer::new(peripherals.SYSTIMER);
esp_hal_embassy::init(systimer.alarm0);
let (_, _, tx_buffer, tx_descriptors) = dma_buffers!(0, 32000);
let dma = Dma::new(peripherals.DMA);
let tx_pins = TxFourBits::new(
peripherals.GPIO1,
peripherals.GPIO2,
peripherals.GPIO3,
peripherals.GPIO4,
);
let mut pin_conf = TxPinConfigWithValidPin::new(tx_pins, peripherals.GPIO5);
let parl_io = ParlIoTxOnly::new(peripherals.PARL_IO, dma.channel0, tx_descriptors, 1.MHz())
.unwrap()
.into_async();
let mut clock_pin = ClkOutPin::new(peripherals.GPIO8);
let mut parl_io_tx = parl_io
.tx
.with_config(
&mut pin_conf,
&mut clock_pin,
0,
SampleEdge::Normal,
BitPackOrder::Msb,
)
.unwrap();
let buffer = tx_buffer;
for i in 0..buffer.len() {
buffer[i] = (i % 255) as u8;
}
loop {
parl_io_tx.write_dma_async(buffer).await.unwrap();
println!("Transferred {} bytes", buffer.len());
Timer::after(Duration::from_millis(500)).await;
}
}

View File

@ -1,77 +0,0 @@
//! 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: 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::{
rtc_cntl::Rtc,
timer::timg::TimerGroup,
touch::{Touch, TouchConfig, TouchPad},
};
use esp_println::println;
#[esp_hal_embassy::main]
async fn main(_spawner: Spawner) {
esp_println::logger::init_logger_from_env();
let peripherals = esp_hal::init(esp_hal::Config::default());
let timg0 = TimerGroup::new(peripherals.TIMG0);
esp_hal_embassy::init(timg0.timer0);
let mut rtc = Rtc::new(peripherals.LPWR);
let touch_pin0 = peripherals.GPIO2;
let touch_pin1 = peripherals.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;
}
}

View File

@ -1,159 +0,0 @@
//! This example demonstrates use of the TWAI peripheral running the embassy
//! executor and asynchronously receiving and transmitting TWAI frames.
//!
//! The `receiver` task waits to receive a frame and puts it into a channel
//! which will be picked up by the `transmitter` task.
//!
//! The `transmitter` task waits for a channel to receive a frame and transmits
//! it.
//!
//! This example should work with another ESP board running the `twai` example
//! with `IS_FIRST_SENDER` set to `true`.
//!
//! The following wiring is assumed:
//! - TX/RX => GPIO2, connected internally and with internal pull-up resistor.
//!
//! ESP1/GND --- ESP2/GND
//! ESP1/GPIO2 --- ESP2/GPIO2
//!
//! Notes for external transceiver use:
//!
//! The default setup assumes that two microcontrollers are connected directly without an external
//! transceiver. If you want to use an external transceiver, you need to:
//! * uncomment the `rx_pin` line
//! * use `new()` function to create the TWAI configuration.
//! * change the `tx_pin` and `rx_pin` to the appropriate pins for your boards.
//% CHIPS: esp32 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: embassy embassy-generic-timers
#![no_std]
#![no_main]
use embassy_executor::Spawner;
use embassy_sync::{blocking_mutex::raw::NoopRawMutex, channel::Channel};
use embedded_can::{Frame, Id};
use esp_backtrace as _;
use esp_hal::{
timer::timg::TimerGroup,
twai::{self, EspTwaiFrame, StandardId, TwaiMode, TwaiRx, TwaiTx},
};
use esp_println::println;
use static_cell::StaticCell;
type TwaiOutbox = Channel<NoopRawMutex, EspTwaiFrame, 16>;
#[embassy_executor::task]
async fn receiver(mut rx: TwaiRx<'static, esp_hal::Async>, channel: &'static TwaiOutbox) -> ! {
loop {
let frame = rx.receive_async().await;
match frame {
Ok(frame) => {
println!("Received a frame:");
print_frame(&frame);
// Send a response
let frame =
EspTwaiFrame::new(StandardId::new(1).unwrap(), &[4, 5, 6, 7, 8]).unwrap();
channel.send(frame).await;
}
Err(e) => {
println!("Receive error: {:?}", e);
}
}
}
}
#[embassy_executor::task]
async fn transmitter(mut tx: TwaiTx<'static, esp_hal::Async>, channel: &'static TwaiOutbox) -> ! {
loop {
let frame = channel.receive().await;
let result = tx.transmit_async(&frame).await;
match result {
Ok(()) => {
println!("Transmitted a frame:");
print_frame(&frame);
}
Err(e) => {
println!("Transmit error: {:?}", e);
}
}
}
}
#[esp_hal_embassy::main]
async fn main(spawner: Spawner) {
esp_println::logger::init_logger_from_env();
let peripherals = esp_hal::init(esp_hal::Config::default());
let timg0 = TimerGroup::new(peripherals.TIMG0);
esp_hal_embassy::init(timg0.timer0);
// Without an external transceiver, we only need a single line between the two MCUs.
let (rx_pin, tx_pin) = peripherals.GPIO2.split();
// Use these if you want to use an external transceiver:
// let tx_pin = peripherals.GPIO2;
// let rx_pin = peripherals.GPIO0;
// The speed of the bus.
const TWAI_BAUDRATE: twai::BaudRate = twai::BaudRate::B125K;
// !!! Use `new` when using a transceiver. `new_no_transceiver` sets TX to open-drain
// Begin configuring the TWAI peripheral. The peripheral is in a reset like
// state that prevents transmission but allows configuration.
let mut twai_config = twai::TwaiConfiguration::new_no_transceiver(
peripherals.TWAI0,
rx_pin,
tx_pin,
TWAI_BAUDRATE,
TwaiMode::Normal,
)
.into_async();
// Partially filter the incoming messages to reduce overhead of receiving
// undesired messages. Note that due to how the hardware filters messages,
// standard ids and extended ids may both match a filter. Frame ids should
// be explicitly checked in the application instead of fully relying on
// these partial acceptance filters to exactly match. A filter that matches
// standard ids of an even value.
const FILTER: twai::filter::SingleStandardFilter =
twai::filter::SingleStandardFilter::new(b"xxxxxxxxxx0", b"x", [b"xxxxxxxx", b"xxxxxxxx"]);
twai_config.set_filter(FILTER);
// Start the peripheral. This locks the configuration settings of the peripheral
// and puts it into operation mode, allowing packets to be sent and
// received.
let twai = twai_config.start();
// Get separate transmit and receive halves of the peripheral.
let (rx, tx) = twai.split();
static CHANNEL: StaticCell<TwaiOutbox> = StaticCell::new();
let channel = &*CHANNEL.init(Channel::new());
spawner.spawn(receiver(rx, channel)).ok();
spawner.spawn(transmitter(tx, channel)).ok();
}
fn print_frame(frame: &EspTwaiFrame) {
// Print different messages based on the frame id type.
match frame.id() {
Id::Standard(id) => {
println!("\tStandard Id: {:?}", id);
}
Id::Extended(id) => {
println!("\tExtended Id: {:?}", id);
}
}
// Print out the frame data or the requested data length code for a remote
// transmission request frame.
if frame.is_data_frame() {
println!("\tData: {:?}", frame.data());
} else {
println!("\tRemote Frame. Data Length Code: {}", frame.dlc());
}
}

View File

@ -1,41 +0,0 @@
//! embassy wait
//!
//! This is an example of asynchronously `Wait`ing for a pin state (boot button) to change.
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: embassy embassy-generic-timers
#![no_std]
#![no_main]
use embassy_executor::Spawner;
use embassy_time::{Duration, Timer};
use esp_backtrace as _;
use esp_hal::{
gpio::{Input, Pull},
timer::timg::TimerGroup,
};
#[esp_hal_embassy::main]
async fn main(_spawner: Spawner) {
esp_println::println!("Init!");
let peripherals = esp_hal::init(esp_hal::Config::default());
let timg0 = TimerGroup::new(peripherals.TIMG0);
esp_hal_embassy::init(timg0.timer0);
cfg_if::cfg_if! {
if #[cfg(any(feature = "esp32", feature = "esp32s2", feature = "esp32s3"))] {
let mut input = Input::new(peripherals.GPIO0, Pull::Down);
} else {
let mut input = Input::new(peripherals.GPIO9, Pull::Down);
}
}
loop {
esp_println::println!("Waiting...");
input.wait_for_rising_edge().await;
esp_println::println!("Ping!");
Timer::after(Duration::from_millis(100)).await;
}
}

View File

@ -1,55 +0,0 @@
//! Control LED by the boot button via ETM without involving the CPU.
//! The following wiring is assumed:
//! - LED => GPIO1
//% CHIPS: esp32c6 esp32h2
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{
etm::Etm,
gpio::{
etm::{Channels, InputConfig, OutputConfig},
Level,
Output,
Pull,
},
prelude::*,
};
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let mut led = Output::new(peripherals.GPIO1, Level::Low);
let button = peripherals.GPIO9;
led.set_high();
// setup ETM
let gpio_ext = Channels::new(peripherals.GPIO_SD);
let led_task = gpio_ext.channel0_task.toggle(
led,
OutputConfig {
open_drain: false,
pull: Pull::None,
initial_state: Level::Low,
},
);
let button_event = gpio_ext
.channel0_event
.falling_edge(button, InputConfig { pull: Pull::Down });
let etm = Etm::new(peripherals.SOC_ETM);
let channel0 = etm.channel0;
// make sure the configured channel doesn't get dropped - dropping it will
// disable the channel
let _configured_channel = channel0.setup(&button_event, &led_task);
// the LED is controlled by the button without involving the CPU
loop {}
}

View File

@ -1,78 +0,0 @@
//! This shows using Parallel IO to output 8 bit parallel data at 1MHz clock
//! rate with a delay of 10ms between each transfer.
//!
//! The following wiring is assumed:
//! - Data pins => GPIO16, GPIO4, GPIO17, GPIO18, GPIO5, GPIO19, GPIO12, and
//! GPIO14
//! - Clock output pin => GPIO25
//!
//! You can use a logic analyzer to see how the pins are used.
//% CHIPS: esp32
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{
delay::Delay,
dma::{Dma, DmaTxBuf},
dma_buffers,
i2s::parallel::{I2sParallel, TxEightBits},
prelude::*,
};
use log::info;
const BUFFER_SIZE: usize = 256;
#[entry]
fn main() -> ! {
esp_println::logger::init_logger(log::LevelFilter::Info);
info!("Starting!");
let peripherals = esp_hal::init(esp_hal::Config::default());
let dma = Dma::new(peripherals.DMA);
let delay = Delay::new();
let dma_channel = dma.i2s1channel;
let i2s = peripherals.I2S1;
let clock = peripherals.GPIO25;
let pins = TxEightBits::new(
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);
let mut parallel = I2sParallel::new(i2s, dma_channel, 1.MHz(), pins, clock);
for (i, data) in tx_buffer.chunks_mut(4).enumerate() {
let offset = i * 4;
// i2s parallel driver expects the buffer to be interleaved
data[0] = (offset + 2) as u8;
data[1] = (offset + 3) as u8;
data[2] = offset as u8;
data[3] = (offset + 1) as u8;
}
let mut tx_buf: DmaTxBuf =
DmaTxBuf::new(tx_descriptors, tx_buffer).expect("DmaTxBuf::new failed");
info!("Sending {} bytes!", BUFFER_SIZE);
loop {
let xfer = match parallel.send(tx_buf) {
Ok(xfer) => xfer,
Err(_) => {
panic!("Failed to send buffer");
}
};
(parallel, tx_buf) = xfer.wait();
delay.delay_millis(10);
}
}

View File

@ -1,76 +0,0 @@
//! This shows how to continuously receive data via I2S.
//!
//! Without an additional I2S source device you can connect 3V3 or GND to DIN
//! to read 0 or 0xFF or connect DIN to WS to read two different values.
//!
//! You can also inspect the MCLK, BCLK and WS with a logic analyzer.
//!
//! The following wiring is assumed:
//! - MCLK => GPIO0 (not supported on ESP32)
//! - BCLK => GPIO2
//! - WS => GPIO4
//! - DIN => GPIO5
//% CHIPS: esp32 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{
dma::Dma,
dma_buffers,
i2s::master::{DataFormat, I2s, Standard},
prelude::*,
};
use esp_println::println;
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let dma = Dma::new(peripherals.DMA);
#[cfg(any(feature = "esp32", feature = "esp32s2"))]
let dma_channel = dma.i2s0channel;
#[cfg(not(any(feature = "esp32", feature = "esp32s2")))]
let dma_channel = dma.channel0;
let (mut rx_buffer, rx_descriptors, _, tx_descriptors) = dma_buffers!(4 * 4092, 0);
// Here we test that the type is
// 1) reasonably simple (or at least this will flag changes that may make it
// more complex)
// 2) can be spelled out by the user
let i2s = I2s::new(
peripherals.I2S0,
Standard::Philips,
DataFormat::Data16Channel16,
44100.Hz(),
dma_channel,
rx_descriptors,
tx_descriptors,
);
#[cfg(not(feature = "esp32"))]
let i2s = i2s.with_mclk(peripherals.GPIO0);
let mut i2s_rx = i2s
.i2s_rx
.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();
println!("Started transfer");
loop {
let avail = transfer.available().unwrap();
if avail > 0 {
let mut rcv = [0u8; 5000];
transfer.pop(&mut rcv[..avail]).unwrap();
println!("Received {:x?}...", &rcv[..30]);
}
}
}

View File

@ -1,65 +0,0 @@
//! Turns on LED with the option to change LED intensity depending on `duty`
//! value. Possible values (`u32`) are in range 0..100.
//!
//! The following wiring is assumed:
//! - LED => GPIO0
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{
ledc::{
channel::{self, ChannelIFace},
timer::{self, TimerIFace},
LSGlobalClkSource,
Ledc,
LowSpeed,
},
prelude::*,
};
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let led = peripherals.GPIO0;
let mut ledc = Ledc::new(peripherals.LEDC);
ledc.set_global_slow_clock(LSGlobalClkSource::APBClk);
let mut lstimer0 = ledc.timer::<LowSpeed>(timer::Number::Timer0);
lstimer0
.configure(timer::config::Config {
duty: timer::config::Duty::Duty5Bit,
clock_source: timer::LSClockSource::APBClk,
frequency: 24.kHz(),
})
.unwrap();
let mut channel0 = ledc.channel(channel::Number::Channel0, led);
channel0
.configure(channel::config::Config {
timer: &lstimer0,
duty_pct: 10,
pin_config: channel::config::PinConfig::PushPull,
})
.unwrap();
channel0.start_duty_fade(0, 100, 2000).expect_err(
"Fading from 0% to 100%, at 24kHz and 5-bit resolution, over 2 seconds, should fail",
);
loop {
// Set up a breathing LED: fade from off to on over a second, then
// from on back off over the next second. Then loop.
channel0.start_duty_fade(0, 100, 1000).unwrap();
while channel0.is_duty_fade_running() {}
channel0.start_duty_fade(100, 0, 1000).unwrap();
while channel0.is_duty_fade_running() {}
}
}

View File

@ -1,48 +0,0 @@
//! This shows a very basic example of running code on the LP core.
//!
//! Code on LP core uses LP_I2C initialized on HP core. For more information
//! check `lp_core_i2c` example in the `esp-lp-hal`.
//!
//! Make sure to first compile the `esp-lp-hal/examples/i2c.rs` example
//!
//! The following wiring is assumed:
//! - SDA => GPIO6
//! - SCL => GPIO7
//% CHIPS: esp32c6
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{
gpio::lp_io::LowPowerOutputOpenDrain,
i2c::lp_i2c::LpI2c,
lp_core::{LpCore, LpCoreWakeupSource},
prelude::*,
};
use esp_println::println;
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
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());
let mut lp_core = LpCore::new(peripherals.LP_CORE);
lp_core.stop();
println!("lp core stopped");
// load code to LP core
let lp_core_code =
load_lp_code!("../esp-lp-hal/target/riscv32imac-unknown-none-elf/release/examples/i2c");
// start LP core
lp_core_code.run(&mut lp_core, LpCoreWakeupSource::HpCpu, lp_i2c);
println!("lpcore run");
loop {}
}

View File

@ -1,65 +0,0 @@
//! This shows a very basic example of running code on the LP core.
//!
//! Code on LP core uses LP_UART initialized on HP core. For more information
//! check `lp_core_uart` example in the `esp-lp-hal.
//!
//! Make sure to first compile the `esp-lp-hal/examples/uart.rs` example
//!
//! The following wiring is assumed:
//! - TX => GPIO5
//! - RX => GPIO4
//% CHIPS: esp32c6
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{
gpio::lp_io::{LowPowerInput, LowPowerOutput},
lp_core::{LpCore, LpCoreWakeupSource},
prelude::*,
uart::{lp_uart::LpUart, Config, Uart},
};
use esp_println::println;
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
// Set up (HP) UART1:
let mut uart1 = Uart::new_with_config(
peripherals.UART1,
Config::default(),
peripherals.GPIO6,
peripherals.GPIO7,
)
.unwrap();
// Set up (LP) UART:
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);
lp_core.stop();
println!("lp core stopped");
// Load code to LP core:
let lp_core_code =
load_lp_code!("../esp-lp-hal/target/riscv32imac-unknown-none-elf/release/examples/uart");
// Start LP core:
lp_core_code.run(&mut lp_core, LpCoreWakeupSource::HpCpu, lp_uart);
println!("lpcore run");
loop {
let read = nb::block!(uart1.read_byte());
match read {
Ok(read) => println!("Read 0x{:02x}", read),
Err(err) => println!("Error {:?}", err),
}
}
}

View File

@ -1,55 +0,0 @@
//! Uses timer0 and operator0 of the MCPWM0 peripheral to output a 50% duty
//! signal at 20 kHz.
//!
//! The following wiring is assumed:
//! - Output pin => GPIO0
//% CHIPS: esp32 esp32c6 esp32h2 esp32s3
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{
mcpwm::{operator::PwmPinConfig, timer::PwmWorkingMode, McPwm, PeripheralClockConfig},
prelude::*,
};
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let pin = peripherals.GPIO0;
// initialize peripheral
cfg_if::cfg_if! {
if #[cfg(feature = "esp32h2")] {
let freq = 40.MHz();
} else {
let freq = 32.MHz();
}
}
let clock_cfg = PeripheralClockConfig::with_frequency(freq).unwrap();
let mut mcpwm = McPwm::new(peripherals.MCPWM0, clock_cfg);
// connect operator0 to timer0
mcpwm.operator0.set_timer(&mcpwm.timer0);
// connect operator0 to pin
let mut pwm_pin = mcpwm
.operator0
.with_pin_a(pin, PwmPinConfig::UP_ACTIVE_HIGH);
// start timer with timestamp values in the range of 0..=99 and a frequency of
// 20 kHz
let timer_clock_cfg = clock_cfg
.timer_clock_with_frequency(99, PwmWorkingMode::Increase, 20.kHz())
.unwrap();
mcpwm.timer0.start(timer_clock_cfg);
// pin will be high 50% of the time
pwm_pin.set_timestamp(50);
loop {}
}

View File

@ -1,52 +0,0 @@
//! This shows how to spawn a task on the second core.
//!
//! The first core will print the value of a counter which is incremented by the
//! second core.
//% CHIPS: esp32 esp32s3
#![no_std]
#![no_main]
use core::{cell::RefCell, ptr::addr_of_mut};
use critical_section::Mutex;
use esp_backtrace as _;
use esp_hal::{
cpu_control::{CpuControl, Stack},
delay::Delay,
prelude::*,
};
use esp_println::println;
static mut APP_CORE_STACK: Stack<8192> = Stack::new();
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let delay = Delay::new();
let counter = Mutex::new(RefCell::new(0u32));
let mut cpu_control = CpuControl::new(peripherals.CPU_CTRL);
let _guard = cpu_control
.start_app_core(unsafe { &mut *addr_of_mut!(APP_CORE_STACK) }, || {
println!("Hello World - Core 1!");
loop {
delay.delay(500.millis());
critical_section::with(|cs| {
let mut val = counter.borrow_ref_mut(cs);
*val = val.wrapping_add(1);
});
}
})
.unwrap();
loop {
delay.delay(1.secs());
let count = critical_section::with(|cs| *counter.borrow_ref(cs));
println!("Hello World - Core 0! Counter is {}", count);
}
}

View File

@ -1,65 +0,0 @@
//! This shows using Parallel IO to input 4 bit parallel data at 1MHz clock
//! rate.
//!
//! The following wiring is assumed:
//! - Data pins => GPIO1, GPIO2, GPIO3, and GPIO4.
//% CHIPS: esp32c6 esp32h2
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{
delay::Delay,
dma::Dma,
dma_buffers,
gpio::NoPin,
parl_io::{BitPackOrder, ParlIoRxOnly, RxFourBits},
prelude::*,
};
use esp_println::println;
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
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(
peripherals.GPIO1,
peripherals.GPIO2,
peripherals.GPIO3,
peripherals.GPIO4,
);
let mut rx_clk_pin = NoPin;
let parl_io =
ParlIoRxOnly::new(peripherals.PARL_IO, dma_channel, rx_descriptors, 1.MHz()).unwrap();
let mut parl_io_rx = parl_io
.rx
.with_config(
&mut rx_pins,
&mut rx_clk_pin,
BitPackOrder::Msb,
Some(0xfff),
)
.unwrap();
let mut buffer = rx_buffer;
buffer.fill(0u8);
let delay = Delay::new();
loop {
let transfer = parl_io_rx.read_dma(&mut buffer).unwrap();
transfer.wait().unwrap();
println!("Received: {:02x?} ...", &buffer[..30]);
delay.delay_millis(500);
}
}

View File

@ -1,81 +0,0 @@
//! This shows using Parallel IO to output 4 bit parallel data at 1MHz clock
//! rate.
//!
//! The following wiring is assumed:
//! - Data pins => GPIO1, GPIO2, GPIO3, and GPIO4
//! - Valid pin => GPIO5 (driven high during an active transfer)
//! - Clock output pin => GPIO6
//!
//! You can use a logic analyzer to see how the pins are used.
//% CHIPS: esp32c6 esp32h2
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{
delay::Delay,
dma::Dma,
dma_buffers,
parl_io::{
BitPackOrder,
ClkOutPin,
ParlIoTxOnly,
SampleEdge,
TxFourBits,
TxPinConfigWithValidPin,
},
prelude::*,
};
use esp_println::println;
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
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(
peripherals.GPIO1,
peripherals.GPIO2,
peripherals.GPIO3,
peripherals.GPIO4,
);
let mut pin_conf = TxPinConfigWithValidPin::new(tx_pins, peripherals.GPIO5);
let parl_io =
ParlIoTxOnly::new(peripherals.PARL_IO, dma_channel, tx_descriptors, 1.MHz()).unwrap();
let mut clock_pin = ClkOutPin::new(peripherals.GPIO6);
let mut parl_io_tx = parl_io
.tx
.with_config(
&mut pin_conf,
&mut clock_pin,
0,
SampleEdge::Normal,
BitPackOrder::Msb,
)
.unwrap();
let buffer = tx_buffer;
for i in 0..buffer.len() {
buffer[i] = (i % 255) as u8;
}
let delay = Delay::new();
loop {
let transfer = parl_io_tx.write_dma(&buffer).unwrap();
transfer.wait().unwrap();
println!("Transferred {} bytes", buffer.len());
delay.delay_millis(500);
}
}

View File

@ -1,103 +0,0 @@
//! PCNT Encoder Demo
//!
//! This example decodes a quadrature encoder.
//!
//! Since the PCNT units reset to zero when they reach their limits
//! we enable an interrupt on the upper and lower limits and
//! track the overflow in an AtomicI32
//!
//! The following wiring is assumed:
//! - Control signal => GPIO4
//! - Edge signal => GPIO5
//% CHIPS: esp32 esp32c6 esp32h2 esp32s2 esp32s3
#![no_std]
#![no_main]
use core::{cell::RefCell, cmp::min, sync::atomic::Ordering};
use critical_section::Mutex;
use esp_backtrace as _;
use esp_hal::{
gpio::{Input, Pull},
interrupt::Priority,
pcnt::{channel, unit, Pcnt},
prelude::*,
};
use esp_println::println;
use portable_atomic::AtomicI32;
static UNIT0: Mutex<RefCell<Option<unit::Unit<'static, 1>>>> = Mutex::new(RefCell::new(None));
static VALUE: AtomicI32 = AtomicI32::new(0);
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
// Set up a pulse counter:
println!("setup pulse counter unit 0");
let mut pcnt = Pcnt::new(peripherals.PCNT);
pcnt.set_interrupt_handler(interrupt_handler);
let u0 = pcnt.unit1;
u0.set_low_limit(Some(-100)).unwrap();
u0.set_high_limit(Some(100)).unwrap();
u0.set_filter(Some(min(10u16 * 80, 1023u16))).unwrap();
u0.clear();
println!("setup channel 0");
let ch0 = &u0.channel0;
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();
ch0.set_ctrl_signal(input_a.clone());
ch0.set_edge_signal(input_b.clone());
ch0.set_ctrl_mode(channel::CtrlMode::Reverse, channel::CtrlMode::Keep);
ch0.set_input_mode(channel::EdgeMode::Increment, channel::EdgeMode::Decrement);
println!("setup channel 1");
let ch1 = &u0.channel1;
ch1.set_ctrl_signal(input_b);
ch1.set_edge_signal(input_a);
ch1.set_ctrl_mode(channel::CtrlMode::Reverse, channel::CtrlMode::Keep);
ch1.set_input_mode(channel::EdgeMode::Decrement, channel::EdgeMode::Increment);
println!("enabling interrupts");
u0.listen();
println!("resume pulse counter unit 0");
u0.resume();
let counter = u0.counter.clone();
critical_section::with(|cs| UNIT0.borrow_ref_mut(cs).replace(u0));
let mut last_value: i32 = 0;
loop {
let value: i32 = counter.get() as i32 + VALUE.load(Ordering::SeqCst);
if value != last_value {
println!("value: {value}");
last_value = value;
}
}
}
#[handler(priority = Priority::Priority2)]
fn interrupt_handler() {
critical_section::with(|cs| {
let mut u0 = UNIT0.borrow_ref_mut(cs);
let u0 = u0.as_mut().unwrap();
if u0.interrupt_is_set() {
let events = u0.events();
if events.high_limit {
VALUE.fetch_add(100, Ordering::SeqCst);
} else if events.low_limit {
VALUE.fetch_add(-100, Ordering::SeqCst);
}
u0.reset_interrupt();
}
});
}

View File

@ -1,29 +0,0 @@
//! This shows how to read selected information from eFuses.
//!
//! Depending on which chip is being targeted, certain efuses may or may not be
//! available.
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{efuse::Efuse, prelude::*};
use esp_println::println;
#[entry]
fn main() -> ! {
println!("MAC address {:02x?}", Efuse::mac_address());
println!("Flash Encryption {:?}", Efuse::flash_encryption());
#[cfg(feature = "esp32")]
{
println!("Core Count {}", Efuse::core_count());
println!("Bluetooth enabled {}", Efuse::is_bluetooth_enabled());
println!("Chip type {:?}", Efuse::chip_type());
println!("Max CPU clock {:?}", Efuse::max_cpu_frequency());
}
loop {}
}

View File

@ -1,124 +0,0 @@
//! Demonstrates decoding pulse sequences with RMT
//!
//! The following wiring is assumed:
//! - Input pin => GPIO4
//! - Output pin => GPIO5
//!
//! Connect GPIO5 to GPIO4
//% CHIPS: esp32 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{
delay::Delay,
gpio::{Level, Output},
prelude::*,
rmt::{PulseCode, Rmt, RxChannel, RxChannelConfig, RxChannelCreator},
};
use esp_println::{print, println};
const WIDTH: usize = 80;
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let mut out = Output::new(peripherals.GPIO5, Level::Low);
cfg_if::cfg_if! {
if #[cfg(feature = "esp32h2")] {
let freq = 32.MHz();
} else {
let freq = 80.MHz();
}
};
let rmt = Rmt::new(peripherals.RMT, freq).unwrap();
let rx_config = RxChannelConfig {
clk_divider: 1,
idle_threshold: 10000,
..RxChannelConfig::default()
};
cfg_if::cfg_if! {
if #[cfg(any(feature = "esp32", feature = "esp32s2"))] {
let mut channel = rmt.channel0.configure(peripherals.GPIO4, rx_config).unwrap();
} else if #[cfg(feature = "esp32s3")] {
let mut channel = rmt.channel7.configure(peripherals.GPIO4, rx_config).unwrap();
} else {
let mut channel = rmt.channel2.configure(peripherals.GPIO4, rx_config).unwrap();
}
}
let delay = Delay::new();
let mut data: [u32; 48] = [PulseCode::empty(); 48];
loop {
for x in data.iter_mut() {
x.reset()
}
let transaction = channel.receive(&mut data).unwrap();
// simulate input
for i in 0u32..5u32 {
out.set_high();
delay.delay_micros(i * 10 + 20);
out.set_low();
delay.delay_micros(i * 20 + 20);
}
match transaction.wait() {
Ok(channel_res) => {
channel = channel_res;
let mut total = 0usize;
for entry in &data[..data.len()] {
if entry.length1() == 0 {
break;
}
total += entry.length1() as usize;
if entry.length2() == 0 {
break;
}
total += entry.length2() as usize;
}
for entry in &data[..data.len()] {
if entry.length1() == 0 {
break;
}
let count = WIDTH / (total / entry.length1() as usize);
let c = if entry.level1() { '-' } else { '_' };
for _ in 0..count + 1 {
print!("{}", c);
}
if entry.length2() == 0 {
break;
}
let count = WIDTH / (total / entry.length2() as usize);
let c = if entry.level2() { '-' } else { '_' };
for _ in 0..count + 1 {
print!("{}", c);
}
}
println!();
}
Err((_err, channel_res)) => {
channel = channel_res;
println!("Error");
}
}
delay.delay_millis(1500);
}
}

View File

@ -1,55 +0,0 @@
//! Demonstrates generating pulse sequences with RMT
//!
//! Connect a logic analyzer to GPIO4 to see the generated pulses.
//!
//! The following wiring is assumed:
//! - generated pulses => GPIO4
//% CHIPS: esp32 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{
delay::Delay,
prelude::*,
rmt::{PulseCode, Rmt, TxChannel, TxChannelConfig, TxChannelCreator},
};
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
cfg_if::cfg_if! {
if #[cfg(feature = "esp32h2")] {
let freq = 32.MHz();
} else {
let freq = 80.MHz();
}
};
let rmt = Rmt::new(peripherals.RMT, freq).unwrap();
let tx_config = TxChannelConfig {
clk_divider: 255,
..TxChannelConfig::default()
};
let mut channel = rmt
.channel0
.configure(peripherals.GPIO4, tx_config)
.unwrap();
let delay = Delay::new();
let mut data = [PulseCode::new(true, 200, false, 50); 20];
data[data.len() - 2] = PulseCode::new(true, 3000, false, 500);
data[data.len() - 1] = PulseCode::empty();
loop {
let transaction = channel.transmit(&data).unwrap();
channel = transaction.wait().unwrap();
delay.delay_millis(500);
}
}

View File

@ -1,26 +0,0 @@
//! Demonstrates the use of the hardware Random Number Generator (RNG)
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{prelude::*, rng::Rng};
use esp_println::println;
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let mut rng = Rng::new(peripherals.RNG);
// Generate a random word (u32):
println!("Random u32: {}", rng.random());
// Fill a buffer with random bytes:
let mut buf = [0u8; 16];
rng.read(&mut buf);
println!("Random bytes: {:?}", buf);
loop {}
}

View File

@ -1,35 +0,0 @@
//! Prints time in milliseconds from the RTC Timer
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
#![no_std]
#![no_main]
use core::time::Duration;
use esp_backtrace as _;
use esp_hal::{delay::Delay, prelude::*, rtc_cntl::Rtc};
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let rtc = Rtc::new(peripherals.LPWR);
let delay = Delay::new();
loop {
esp_println::println!(
"rtc time in milliseconds is {}",
rtc.current_time().and_utc().timestamp_millis()
);
delay.delay_millis(1000);
// Set the time to half a second in the past
let new_time = rtc.current_time() - Duration::from_millis(500);
esp_println::println!(
"setting rtc time to {} milliseconds",
new_time.and_utc().timestamp_millis()
);
rtc.set_current_time(new_time);
}
}

View File

@ -1,55 +0,0 @@
//! This example demonstrates the RTC Watchdog Timer (RWDT).
//!
//! The RWDT is initially configured to trigger an interrupt after a given
//! timeout. Then, upon expiration, the RWDT is restarted and then reconfigured
//! to reset both the main system and the RTC.
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
#![no_std]
#![no_main]
use core::cell::RefCell;
use critical_section::Mutex;
use esp_backtrace as _;
use esp_hal::{
interrupt::Priority,
prelude::*,
rtc_cntl::{Rtc, Rwdt, RwdtStage},
};
use esp_println::println;
static RWDT: Mutex<RefCell<Option<Rwdt>>> = Mutex::new(RefCell::new(None));
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let mut rtc = Rtc::new(peripherals.LPWR);
rtc.set_interrupt_handler(interrupt_handler);
rtc.rwdt.enable();
rtc.rwdt.set_timeout(RwdtStage::Stage0, 2.secs());
rtc.rwdt.listen();
critical_section::with(|cs| RWDT.borrow_ref_mut(cs).replace(rtc.rwdt));
loop {}
}
#[handler(priority = Priority::min())]
fn interrupt_handler() {
critical_section::with(|cs| {
println!("RWDT Interrupt");
let mut rwdt = RWDT.borrow_ref_mut(cs);
let rwdt = rwdt.as_mut().unwrap();
rwdt.clear_interrupt();
println!("Restarting in 5 seconds...");
rwdt.set_timeout(RwdtStage::Stage0, 5.secs());
rwdt.unlisten();
});
}

View File

@ -1,91 +0,0 @@
//! This shows some of the interrupts that can be generated by UART/Serial.
//! Use a proper serial terminal to connect to the board (espmonitor and
//! espflash won't work)
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
#![no_std]
#![no_main]
use core::{cell::RefCell, fmt::Write};
use critical_section::Mutex;
use esp_backtrace as _;
use esp_hal::{
delay::Delay,
prelude::*,
uart::{AtCmdConfig, Config, Uart, UartInterrupt},
Blocking,
};
static SERIAL: Mutex<RefCell<Option<Uart<Blocking>>>> = Mutex::new(RefCell::new(None));
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let delay = Delay::new();
// Default pins for Uart/Serial communication
cfg_if::cfg_if! {
if #[cfg(feature = "esp32")] {
let (tx_pin, rx_pin) = (peripherals.GPIO1, peripherals.GPIO3);
} else if #[cfg(feature = "esp32c2")] {
let (tx_pin, rx_pin) = (peripherals.GPIO20, peripherals.GPIO19);
} else if #[cfg(feature = "esp32c3")] {
let (tx_pin, rx_pin) = (peripherals.GPIO21, peripherals.GPIO20);
} else if #[cfg(feature = "esp32c6")] {
let (tx_pin, rx_pin) = (peripherals.GPIO16, peripherals.GPIO17);
} else if #[cfg(feature = "esp32h2")] {
let (tx_pin, rx_pin) = (peripherals.GPIO24, peripherals.GPIO23);
} else if #[cfg(any(feature = "esp32s2", feature = "esp32s3"))] {
let (tx_pin, rx_pin) = (peripherals.GPIO43, peripherals.GPIO44);
}
}
let config = Config::default().rx_fifo_full_threshold(30);
let mut uart0 = Uart::new_with_config(peripherals.UART0, config, tx_pin, rx_pin).unwrap();
uart0.set_interrupt_handler(interrupt_handler);
critical_section::with(|cs| {
uart0.set_at_cmd(AtCmdConfig::new(None, None, None, b'#', None));
uart0.listen(UartInterrupt::AtCmd | UartInterrupt::RxFifoFull);
SERIAL.borrow_ref_mut(cs).replace(uart0);
});
loop {
critical_section::with(|cs| {
let mut serial = SERIAL.borrow_ref_mut(cs);
let serial = serial.as_mut().unwrap();
writeln!(serial, "Hello World! Send a single `#` character or send at least 30 characters and see the interrupts trigger.").ok();
});
delay.delay(1.secs());
}
}
#[handler]
fn interrupt_handler() {
critical_section::with(|cs| {
let mut serial = SERIAL.borrow_ref_mut(cs);
let serial = serial.as_mut().unwrap();
let mut cnt = 0;
while let nb::Result::Ok(_c) = serial.read_byte() {
cnt += 1;
}
writeln!(serial, "Read {} bytes", cnt,).ok();
let pending_interrupts = serial.interrupts();
writeln!(
serial,
"Interrupt AT-CMD: {} RX-FIFO-FULL: {}",
pending_interrupts.contains(UartInterrupt::AtCmd),
pending_interrupts.contains(UartInterrupt::RxFifoFull),
)
.ok();
serial.clear_interrupts(UartInterrupt::AtCmd | UartInterrupt::RxFifoFull);
});
}

View File

@ -1,120 +0,0 @@
//! Software Interrupts
//!
//! An example of how software interrupts can be raised and reset
//! Should rotate through all of the available interrupts printing their number
//! when raised.
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
#![no_std]
#![no_main]
use core::cell::RefCell;
use critical_section::Mutex;
use esp_backtrace as _;
use esp_hal::{
delay::Delay,
interrupt::software::{SoftwareInterrupt, SoftwareInterruptControl},
prelude::*,
};
static SWINT0: Mutex<RefCell<Option<SoftwareInterrupt<0>>>> = Mutex::new(RefCell::new(None));
static SWINT1: Mutex<RefCell<Option<SoftwareInterrupt<1>>>> = Mutex::new(RefCell::new(None));
static SWINT2: Mutex<RefCell<Option<SoftwareInterrupt<2>>>> = Mutex::new(RefCell::new(None));
static SWINT3: Mutex<RefCell<Option<SoftwareInterrupt<3>>>> = Mutex::new(RefCell::new(None));
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let mut sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT);
critical_section::with(|cs| {
sw_ints
.software_interrupt0
.set_interrupt_handler(swint0_handler);
SWINT0
.borrow_ref_mut(cs)
.replace(sw_ints.software_interrupt0);
sw_ints
.software_interrupt1
.set_interrupt_handler(swint1_handler);
SWINT1
.borrow_ref_mut(cs)
.replace(sw_ints.software_interrupt1);
sw_ints
.software_interrupt2
.set_interrupt_handler(swint2_handler);
SWINT2
.borrow_ref_mut(cs)
.replace(sw_ints.software_interrupt2);
sw_ints
.software_interrupt3
.set_interrupt_handler(swint3_handler);
SWINT3
.borrow_ref_mut(cs)
.replace(sw_ints.software_interrupt3);
});
let delay = Delay::new();
let mut counter = 0;
loop {
delay.delay_millis(500);
match counter {
0 => critical_section::with(|cs| {
SWINT0.borrow_ref(cs).as_ref().unwrap().raise();
}),
1 => critical_section::with(|cs| {
SWINT1.borrow_ref(cs).as_ref().unwrap().raise();
}),
2 => critical_section::with(|cs| {
SWINT2.borrow_ref(cs).as_ref().unwrap().raise();
}),
3 => {
critical_section::with(|cs| {
SWINT3.borrow_ref(cs).as_ref().unwrap().raise();
});
counter = -1
}
_ => {}
}
counter += 1;
}
}
#[handler]
fn swint0_handler() {
esp_println::println!("SW interrupt0");
critical_section::with(|cs| {
SWINT0.borrow_ref(cs).as_ref().unwrap().reset();
});
}
#[handler]
fn swint1_handler() {
esp_println::println!("SW interrupt1");
critical_section::with(|cs| {
SWINT1.borrow_ref(cs).as_ref().unwrap().reset();
});
}
#[handler]
fn swint2_handler() {
esp_println::println!("SW interrupt2");
critical_section::with(|cs| {
SWINT2.borrow_ref(cs).as_ref().unwrap().reset();
});
}
#[handler]
fn swint3_handler() {
esp_println::println!("SW interrupt3");
critical_section::with(|cs| {
SWINT3.borrow_ref(cs).as_ref().unwrap().reset();
});
}

View File

@ -1,106 +0,0 @@
//! SPI loopback test using DMA
//!
//! The following wiring is assumed:
//! - SCLK => GPIO0
//! - MISO => GPIO2
//! - MOSI => GPIO4
//! - CS => GPIO5
//!
//! Depending on your target and the board you are using you have to change the
//! pins.
//!
//! This example transfers data via SPI.
//! Connect MISO and MOSI pins to see the outgoing data is read as incoming
//! data.
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{
delay::Delay,
dma::{Dma, DmaRxBuf, DmaTxBuf},
dma_buffers,
prelude::*,
spi::{
master::{Config, Spi},
SpiMode,
},
};
use esp_println::println;
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let sclk = peripherals.GPIO0;
let miso = peripherals.GPIO2;
let mosi = peripherals.GPIO4;
let cs = peripherals.GPIO5;
let dma = Dma::new(peripherals.DMA);
cfg_if::cfg_if! {
if #[cfg(any(feature = "esp32", feature = "esp32s2"))] {
let dma_channel = dma.spi2channel;
} else {
let dma_channel = dma.channel0;
}
}
let (rx_buffer, rx_descriptors, tx_buffer, tx_descriptors) = dma_buffers!(32000);
let mut dma_rx_buf = DmaRxBuf::new(rx_descriptors, rx_buffer).unwrap();
let mut dma_tx_buf = DmaTxBuf::new(tx_descriptors, tx_buffer).unwrap();
let mut spi = Spi::new_with_config(
peripherals.SPI2,
Config {
frequency: 100.kHz(),
mode: SpiMode::Mode0,
..Config::default()
},
)
.with_sck(sclk)
.with_mosi(mosi)
.with_miso(miso)
.with_cs(cs)
.with_dma(dma_channel);
let delay = Delay::new();
let mut i = 0;
for (i, v) in dma_tx_buf.as_mut_slice().iter_mut().enumerate() {
*v = (i % 255) as u8;
}
loop {
dma_tx_buf.as_mut_slice()[0] = i;
*dma_tx_buf.as_mut_slice().last_mut().unwrap() = i;
i = i.wrapping_add(1);
let transfer = spi
.transfer(dma_rx_buf, dma_tx_buf)
.map_err(|e| e.0)
.unwrap();
// here we could do something else while DMA transfer is in progress
let mut n = 0;
// Check is_done until the transfer is almost done (32000 bytes at 100kHz is
// 2.56 seconds), then move to wait().
while !transfer.is_done() && n < 10 {
delay.delay_millis(250);
n += 1;
}
(spi, (dma_rx_buf, dma_tx_buf)) = transfer.wait();
println!(
"{:x?} .. {:x?}",
&dma_rx_buf.as_slice()[..10],
&dma_rx_buf.as_slice().last_chunk::<10>().unwrap()
);
delay.delay_millis(250);
}
}

View File

@ -1,46 +0,0 @@
//! This shows a very basic example of running code on the ULP RISCV core.
//!
//! Code on ULP core just increments a counter and blinks with LED. The current
//! value is printed by the HP core.
//!
//! The following wiring is assumed:
//! - LED => GPIO1
//% CHIPS: esp32s2 esp32s3
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{gpio::rtc_io::*, prelude::*, ulp_core};
use esp_println::{print, println};
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let pin = LowPowerOutput::new(peripherals.GPIO1);
let mut ulp_core = ulp_core::UlpCore::new(peripherals.ULP_RISCV_CORE);
#[cfg(feature = "esp32s3")]
{
ulp_core.stop();
println!("ulp core stopped");
}
// load code to LP core
let lp_core_code =
load_lp_code!("../esp-lp-hal/target/riscv32imc-unknown-none-elf/release/examples/blinky");
// start LP core
lp_core_code.run(&mut ulp_core, ulp_core::UlpCoreWakeupSource::HpCpu, pin);
println!("ulpcore run");
let data = (0x5000_0400) as *mut u32;
loop {
print!("Current {:x} \u{000d}", unsafe {
data.read_volatile()
});
}
}

View File

@ -1,63 +0,0 @@
//! This shows how to output text via USB Serial/JTAG.
//!
//! You need to connect via the Serial/JTAG interface to see any output.
//! Most dev-kits use a USB-UART-bridge - in that case you won't see any output.
//!
//! Windows Users: Flashing and then monitoring via espflash will result in any keypress freezing the application.
//! Please use another serial monitor (e.g. `putty`) on Windows
//! See https://github.com/esp-rs/espflash/issues/654
//% CHIPS: esp32c3 esp32c6 esp32h2 esp32s3
#![no_std]
#![no_main]
use core::{cell::RefCell, fmt::Write};
use critical_section::Mutex;
use esp_backtrace as _;
use esp_hal::{delay::Delay, prelude::*, usb_serial_jtag::UsbSerialJtag, Blocking};
static USB_SERIAL: Mutex<RefCell<Option<UsbSerialJtag<'static, Blocking>>>> =
Mutex::new(RefCell::new(None));
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let delay = Delay::new();
let mut usb_serial = UsbSerialJtag::new(peripherals.USB_DEVICE);
usb_serial.set_interrupt_handler(usb_device);
usb_serial.listen_rx_packet_recv_interrupt();
critical_section::with(|cs| USB_SERIAL.borrow_ref_mut(cs).replace(usb_serial));
loop {
critical_section::with(|cs| {
writeln!(
USB_SERIAL.borrow_ref_mut(cs).as_mut().unwrap(),
"Hello world!"
)
.ok();
});
delay.delay(1.secs());
}
}
#[handler]
fn usb_device() {
critical_section::with(|cs| {
let mut usb_serial = USB_SERIAL.borrow_ref_mut(cs);
let usb_serial = usb_serial.as_mut().unwrap();
writeln!(usb_serial, "USB serial interrupt").unwrap();
while let nb::Result::Ok(c) = usb_serial.read_byte() {
writeln!(usb_serial, "Read byte: {:02x}", c).unwrap();
}
usb_serial.reset_rx_packet_recv_interrupt();
});
}

9
qa-test/build.rs Normal file
View File

@ -0,0 +1,9 @@
fn main() {
// Allow building QA tests in CI in debug mode
println!("cargo:rustc-check-cfg=cfg(is_not_release)");
println!("cargo:rerun-if-env-changed=CI");
#[cfg(debug_assertions)]
if std::env::var("CI").is_err() {
println!("cargo::rustc-cfg=is_not_release");
}
}

View File

@ -12,7 +12,7 @@
//! - DIN => GPIO5
//% CHIPS: esp32 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: embassy embassy-generic-timers
//% FEATURES: embassy-generic-timers
#![no_std]
#![no_main]

View File

@ -1,110 +0,0 @@
//! This shows how to transmit data continuously via I2S.
//!
//! Without an additional I2S sink device you can inspect the MCLK, BCLK, WS
//! and DOUT with a logic analyzer.
//!
//! You can also connect e.g. a PCM510x to hear an annoying loud sine tone (full
//! scale), so turn down the volume before running this example.
//!
//! The following wiring is assumed:
//! - BCLK => GPIO2
//! - WS => GPIO4
//! - DOUT => GPIO5
//!
//! PCM510x:
//! | Pin | Connected to |
//! |-------|-----------------|
//! | BCK | GPIO0 |
//! | DIN | GPIO2 |
//! | LRCK | GPIO1 |
//! | SCK | Gnd |
//! | GND | Gnd |
//! | VIN | +3V3 |
//! | FLT | Gnd |
//! | FMT | Gnd |
//! | DEMP | Gnd |
//! | XSMT | +3V3 |
//% CHIPS: esp32 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
#![no_std]
#![no_main]
use esp_backtrace as _;
use esp_hal::{
dma::Dma,
dma_buffers,
i2s::master::{DataFormat, I2s, Standard},
prelude::*,
};
const SINE: [i16; 64] = [
0, 3211, 6392, 9511, 12539, 15446, 18204, 20787, 23169, 25329, 27244, 28897, 30272, 31356,
32137, 32609, 32767, 32609, 32137, 31356, 30272, 28897, 27244, 25329, 23169, 20787, 18204,
15446, 12539, 9511, 6392, 3211, 0, -3211, -6392, -9511, -12539, -15446, -18204, -20787, -23169,
-25329, -27244, -28897, -30272, -31356, -32137, -32609, -32767, -32609, -32137, -31356, -30272,
-28897, -27244, -25329, -23169, -20787, -18204, -15446, -12539, -9511, -6392, -3211,
];
#[entry]
fn main() -> ! {
let peripherals = esp_hal::init(esp_hal::Config::default());
let dma = Dma::new(peripherals.DMA);
#[cfg(any(feature = "esp32", feature = "esp32s2"))]
let dma_channel = dma.i2s0channel;
#[cfg(not(any(feature = "esp32", feature = "esp32s2")))]
let dma_channel = dma.channel0;
let (_, rx_descriptors, tx_buffer, tx_descriptors) = dma_buffers!(0, 32000);
let i2s = I2s::new(
peripherals.I2S0,
Standard::Philips,
DataFormat::Data16Channel16,
44100.Hz(),
dma_channel,
rx_descriptors,
tx_descriptors,
);
let mut i2s_tx = i2s
.i2s_tx
.with_bclk(peripherals.GPIO2)
.with_ws(peripherals.GPIO4)
.with_dout(peripherals.GPIO5)
.build();
let data =
unsafe { core::slice::from_raw_parts(&SINE as *const _ as *const u8, SINE.len() * 2) };
let mut idx = 0;
for i in 0..usize::min(data.len(), tx_buffer.len()) {
tx_buffer[i] = data[idx];
idx += 1;
if idx >= data.len() {
idx = 0;
}
}
let mut filler = [0u8; 10000];
let mut transfer = i2s_tx.write_dma_circular(&tx_buffer).unwrap();
loop {
let avail = transfer.available().unwrap();
if avail > 0 {
let avail = usize::min(10000, avail);
for bidx in 0..avail {
filler[bidx] = data[idx];
idx += 1;
if idx >= data.len() {
idx = 0;
}
}
transfer.push(&filler[0..avail]).unwrap();
}
}
}

View File

@ -1,8 +1,8 @@
//! Demonstrates deep sleep with timer, using low and high level pins as wakeup sources.
//! Demonstrates deep sleep with timer, using low and high level pins as wakeup
//! sources.
//!
//! The following wiring is assumed:
//! - ext1 wakeup pin => GPIO2 (low level)
//! => GPIO3 (high level)
//! - ext1 wakeup pin => GPIO2 (low level) / GPIO3 (high level)
//% CHIPS: esp32c6