Newtype fugit Rate, Instant and Duration (#3083)

* Newtype fugit Rate, Instant and Duration

* Document, remove time::now

* Fix perf

* Tweak docs
This commit is contained in:
Dániel Buga 2025-02-04 18:23:08 +01:00 committed by GitHub
parent fe53061931
commit 8c69e8cb51
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
115 changed files with 1052 additions and 680 deletions

View File

@ -10,7 +10,7 @@ use embassy_time_driver::Driver;
use esp_hal::{
interrupt::{InterruptHandler, Priority},
sync::Locked,
time::{now, ExtU64},
time::{Duration, Instant},
timer::OneShotTimer,
Blocking,
};
@ -203,11 +203,10 @@ impl EmbassyTimer {
/// Returns `true` if the timer was armed, `false` if the timestamp is in
/// the past.
fn arm(timer: &mut Timer, timestamp: u64) -> bool {
let now = now().duration_since_epoch();
let ts = timestamp.micros();
let now = Instant::now().duration_since_epoch().as_micros();
if ts > now {
let timeout = ts - now;
if timestamp > now {
let timeout = Duration::from_micros(timestamp - now);
unwrap!(timer.schedule(timeout));
true
} else {
@ -295,7 +294,7 @@ impl EmbassyTimer {
impl Driver for EmbassyTimer {
fn now(&self) -> u64 {
now().ticks()
Instant::now().duration_since_epoch().as_micros()
}
fn schedule_wake(&self, at: u64, waker: &core::task::Waker) {

View File

@ -60,7 +60,9 @@ impl TimerQueue {
}
pub fn dispatch(&self) {
let now = esp_hal::time::now().ticks();
let now = esp_hal::time::Instant::now()
.duration_since_epoch()
.as_micros();
self.arm_alarm(now);
}

View File

@ -8,9 +8,11 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
## [Unreleased]
### Added
- SPI: Added support for 3-wire SPI (#2919)
- UART: Add separate config for Rx and Tx (#2965)
- Added accessor methods to config structs (#3011)
- `esp_hal::time::{Rate, Duration, Instant}` (#3083)
- Async support for ADC oneshot reads for ESP32C2, ESP32C3, ESP32C6 and ESP32H2 (#2925, #3082)
### Changed
@ -33,6 +35,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
- `flip-link` feature is now a config option (`ESP_HAL_CONFIG_FLIP_LINK`) (#3001)
- Migrate AES driver to DMA move API (#3084)
- Removed features `psram-quad` and `psram-octal` - replaced by `psram` and the `ESP_HAL_CONFIG_PSRAM_MODE` (`quad`/`octal`) (#3001)
- The `esp_hal::time` module no longer reexports `fugit` types (#3083)
- I2C: Async functions are postfixed with `_async`, non-async functions are available in async-mode (#3056)
@ -48,6 +51,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
- OutputOpenDrain has been removed (#3029)
- The fields of config structs are no longer public (#3011)
- Removed the dysfunctional `DmaChannel::set_priority` function (#3088)
- `esp_hal::time::now()`, which has been replaced by `esp_hal::time::Instant::now()` (#3083)
## [0.23.1] - 2025-01-15

View File

@ -266,6 +266,7 @@ All async functions now include the `_async` postfix. Additionally the non-async
```diff
- let result = i2c.write_read(0x77, &[0xaa], &mut data).await;
+ let result = i2c.write_read_async(0x77, &[0xaa], &mut data).await;
```
## ADC Changes
@ -277,3 +278,17 @@ NOTE: Async support is only supported in ESP32C3 and ESP32C6 for now
- Adc<'d, ADC>
+ Adc<'d, ADC, Blocking>
```
## time API changes
ESP-HAL no longer publicly exposes `fugit` and no longer exposes the concept of a `tick`.
This comes with a number of changes:
- The `RateExtU32` and similar traits are no longer used, which means `.kHz()` and similar suffix
conversions are no longer available. A number of matching constructors are available. For example,
instead of `1.MHz()` you need to write `Rate::from_mhz(1)`.
- Methods on `esp_hal::time` types are named differently.
- Getters are prefixed with `as_`, e.g. `Duration::as_secs`.
- Constructors are prefixed with `from`, e.g. `Rate::from_mhz`.
- A number of functions that convert from a number into a time type (e.g. `Duration::from_ticks`)
are not available. Use conversions from physical units of time, like `Duration::from_millis`.

View File

@ -37,6 +37,7 @@ pub(crate) fn set_cpu_clock(cpu_clock_speed: CpuClock) {
} as u8)
});
// FIXME untangle this
let value = (((80 * MHZ) >> 12) & UINT16_MAX) | ((((80 * MHZ) >> 12) & UINT16_MAX) << 16);
rtc_cntl.store5().modify(|_, w| w.scratch5().bits(value));
}

View File

@ -1,5 +1,3 @@
use core::ops::Div;
use crate::{
clock::{Clock, CpuClock},
rom,
@ -24,6 +22,5 @@ pub(crate) fn set_cpu_clock(cpu_clock_speed: CpuClock) {
});
}
let ticks_per_us = cpu_clock_speed.frequency().div(1_000_000);
rom::ets_update_cpu_frequency_rom(ticks_per_us.raw());
rom::ets_update_cpu_frequency_rom(cpu_clock_speed.frequency().as_mhz());
}

View File

@ -44,10 +44,9 @@
//! # }
//! ```
use fugit::HertzU32;
#[cfg(any(esp32, esp32c2))]
use crate::rtc_cntl::RtcClock;
use crate::time::Rate;
#[cfg_attr(esp32, path = "clocks_ll/esp32.rs")]
#[cfg_attr(esp32c2, path = "clocks_ll/esp32c2.rs")]
@ -61,17 +60,17 @@ pub(crate) mod clocks_ll;
/// Clock properties
#[doc(hidden)]
pub trait Clock {
/// Frequency of the clock in [Hertz](fugit::HertzU32), using [fugit] types.
fn frequency(&self) -> HertzU32;
/// Frequency of the clock in [Rate].
fn frequency(&self) -> Rate;
/// Frequency of the clock in Megahertz
fn mhz(&self) -> u32 {
self.frequency().to_MHz()
self.frequency().as_mhz()
}
/// Frequency of the clock in Hertz
fn hz(&self) -> u32 {
self.frequency().to_Hz()
self.frequency().as_hz()
}
}
@ -136,8 +135,8 @@ impl CpuClock {
}
impl Clock for CpuClock {
fn frequency(&self) -> HertzU32 {
HertzU32::MHz(*self as u32)
fn frequency(&self) -> Rate {
Rate::from_mhz(*self as u32)
}
}
@ -160,15 +159,15 @@ pub enum XtalClock {
}
impl Clock for XtalClock {
fn frequency(&self) -> HertzU32 {
fn frequency(&self) -> Rate {
match self {
#[cfg(any(esp32, esp32c2))]
XtalClock::_26M => HertzU32::MHz(26),
XtalClock::_26M => Rate::from_mhz(26),
#[cfg(any(esp32c3, esp32h2, esp32s3))]
XtalClock::_32M => HertzU32::MHz(32),
XtalClock::_32M => Rate::from_mhz(32),
#[cfg(not(esp32h2))]
XtalClock::_40M => HertzU32::MHz(40),
XtalClock::Other(mhz) => HertzU32::MHz(*mhz),
XtalClock::_40M => Rate::from_mhz(40),
XtalClock::Other(mhz) => Rate::from_mhz(*mhz),
}
}
}
@ -199,28 +198,28 @@ pub(crate) enum PllClock {
}
impl Clock for PllClock {
fn frequency(&self) -> HertzU32 {
fn frequency(&self) -> Rate {
match self {
#[cfg(esp32h2)]
Self::Pll8MHz => HertzU32::MHz(8),
Self::Pll8MHz => Rate::from_mhz(8),
#[cfg(any(esp32c6, esp32h2))]
Self::Pll48MHz => HertzU32::MHz(48),
Self::Pll48MHz => Rate::from_mhz(48),
#[cfg(esp32h2)]
Self::Pll64MHz => HertzU32::MHz(64),
Self::Pll64MHz => Rate::from_mhz(64),
#[cfg(esp32c6)]
Self::Pll80MHz => HertzU32::MHz(80),
Self::Pll80MHz => Rate::from_mhz(80),
#[cfg(esp32h2)]
Self::Pll96MHz => HertzU32::MHz(96),
Self::Pll96MHz => Rate::from_mhz(96),
#[cfg(esp32c6)]
Self::Pll120MHz => HertzU32::MHz(120),
Self::Pll120MHz => Rate::from_mhz(120),
#[cfg(esp32c6)]
Self::Pll160MHz => HertzU32::MHz(160),
Self::Pll160MHz => Rate::from_mhz(160),
#[cfg(esp32c6)]
Self::Pll240MHz => HertzU32::MHz(240),
Self::Pll240MHz => Rate::from_mhz(240),
#[cfg(not(any(esp32c2, esp32c6, esp32h2)))]
Self::Pll320MHz => HertzU32::MHz(320),
Self::Pll320MHz => Rate::from_mhz(320),
#[cfg(not(esp32h2))]
Self::Pll480MHz => HertzU32::MHz(480),
Self::Pll480MHz => Rate::from_mhz(480),
}
}
}
@ -238,15 +237,15 @@ pub(crate) enum ApbClock {
}
impl Clock for ApbClock {
fn frequency(&self) -> HertzU32 {
fn frequency(&self) -> Rate {
match self {
#[cfg(esp32h2)]
ApbClock::ApbFreq32MHz => HertzU32::MHz(32),
ApbClock::ApbFreq32MHz => Rate::from_mhz(32),
#[cfg(not(esp32h2))]
ApbClock::ApbFreq40MHz => HertzU32::MHz(40),
ApbClock::ApbFreq40MHz => Rate::from_mhz(40),
#[cfg(not(esp32h2))]
ApbClock::ApbFreq80MHz => HertzU32::MHz(80),
ApbClock::ApbFreqOther(mhz) => HertzU32::MHz(*mhz),
ApbClock::ApbFreq80MHz => Rate::from_mhz(80),
ApbClock::ApbFreqOther(mhz) => Rate::from_mhz(*mhz),
}
}
}
@ -258,37 +257,37 @@ impl Clock for ApbClock {
#[doc(hidden)]
pub struct Clocks {
/// CPU clock frequency
pub cpu_clock: HertzU32,
pub cpu_clock: Rate,
/// APB clock frequency
pub apb_clock: HertzU32,
pub apb_clock: Rate,
/// XTAL clock frequency
pub xtal_clock: HertzU32,
pub xtal_clock: Rate,
/// I2C clock frequency
#[cfg(esp32)]
pub i2c_clock: HertzU32,
pub i2c_clock: Rate,
/// PWM clock frequency
#[cfg(esp32)]
pub pwm_clock: HertzU32,
pub pwm_clock: Rate,
/// Crypto PWM clock frequency
#[cfg(esp32s3)]
pub crypto_pwm_clock: HertzU32,
pub crypto_pwm_clock: Rate,
/// Crypto clock frequency
#[cfg(any(esp32c6, esp32h2))]
pub crypto_clock: HertzU32,
pub crypto_clock: Rate,
/// PLL 48M clock frequency (fixed)
#[cfg(esp32h2)]
pub pll_48m_clock: HertzU32,
pub pll_48m_clock: Rate,
/// PLL 96M clock frequency (fixed)
#[cfg(esp32h2)]
pub pll_96m_clock: HertzU32,
pub pll_96m_clock: Rate,
}
static mut ACTIVE_CLOCKS: Option<Clocks> = None;
@ -318,7 +317,8 @@ impl Clocks {
/// This function will run the frequency estimation if called before
/// [`crate::init()`].
#[cfg(systimer)]
pub(crate) fn xtal_freq() -> HertzU32 {
#[inline]
pub(crate) fn xtal_freq() -> Rate {
if let Some(clocks) = Self::try_get() {
clocks.xtal_clock
} else {
@ -356,13 +356,13 @@ impl Clocks {
Self {
cpu_clock: cpu_clock_speed.frequency(),
apb_clock: HertzU32::MHz(80),
xtal_clock: HertzU32::MHz(xtal_freq.mhz()),
i2c_clock: HertzU32::MHz(80),
apb_clock: Rate::from_mhz(80),
xtal_clock: Rate::from_mhz(xtal_freq.mhz()),
i2c_clock: Rate::from_mhz(80),
// The docs are unclear here. pwm_clock seems to be tied to clocks.apb_clock
// while simultaneously being fixed at 160 MHz.
// Testing showed 160 MHz to be correct for current clock configurations.
pwm_clock: HertzU32::MHz(160),
pwm_clock: Rate::from_mhz(160),
}
}
}
@ -476,7 +476,7 @@ impl Clocks {
cpu_clock: cpu_clock_speed.frequency(),
apb_clock: apb_freq.frequency(),
xtal_clock: xtal_freq.frequency(),
crypto_clock: HertzU32::MHz(160),
crypto_clock: Rate::from_mhz(160),
}
}
}
@ -513,9 +513,9 @@ impl Clocks {
cpu_clock: cpu_clock_speed.frequency(),
apb_clock: apb_freq.frequency(),
xtal_clock: xtal_freq.frequency(),
pll_48m_clock: HertzU32::MHz(48),
crypto_clock: HertzU32::MHz(96),
pll_96m_clock: HertzU32::MHz(96),
pll_48m_clock: Rate::from_mhz(48),
crypto_clock: Rate::from_mhz(96),
pll_96m_clock: Rate::from_mhz(96),
}
}
}
@ -536,7 +536,7 @@ impl Clocks {
Self {
cpu_clock: cpu_clock_speed.frequency(),
apb_clock: HertzU32::MHz(80),
apb_clock: Rate::from_mhz(80),
xtal_clock: xtal_freq.frequency(),
}
}
@ -558,9 +558,9 @@ impl Clocks {
Self {
cpu_clock: cpu_clock_speed.frequency(),
apb_clock: HertzU32::MHz(80),
apb_clock: Rate::from_mhz(80),
xtal_clock: xtal_freq.frequency(),
crypto_pwm_clock: HertzU32::MHz(160),
crypto_pwm_clock: Rate::from_mhz(160),
}
}
}

View File

@ -24,21 +24,24 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! use esp_hal::clock::CpuClock;
//! use esp_hal::time::Duration;
//!
//! let config =
//! esp_hal::Config::default().with_cpu_clock(CpuClock::max()).
//! with_watchdog(esp_hal::config::WatchdogConfig::default().
//! with_rwdt(esp_hal::config::WatchdogStatus::Enabled(fugit::MicrosDurationU64::millis(1000u64))));
//! with_rwdt(esp_hal::config::WatchdogStatus::Enabled(Duration::from_millis(1000u64))));
//! let peripherals = esp_hal::init(config);
//! # Ok(())
//! # }
//! ```
use crate::time::Duration;
/// Watchdog status.
#[derive(Default, PartialEq, Clone, Copy)]
pub enum WatchdogStatus {
/// Enables a watchdog timer with the specified timeout.
Enabled(fugit::MicrosDurationU64),
Enabled(Duration),
/// Disables the watchdog timer.
#[default]
Disabled,

View File

@ -3,7 +3,7 @@
//! ## Overview
//!
//! The Delay driver provides blocking delay functionalities using the
//! [now] function.
//! [`Instant`] struct.
//!
//! ## Configuration
//!
@ -30,14 +30,10 @@
//!
//! [DelayNs]: https://docs.rs/embedded-hal/1.0.0/embedded_hal/delay/trait.DelayNs.html
//! [embedded-hal]: https://docs.rs/embedded-hal/1.0.0/embedded_hal/delay/index.html
//! [now]: crate::time::now
pub use fugit::MicrosDurationU64;
use crate::time::{Duration, Instant};
/// Delay driver
///
/// Uses the `SYSTIMER` peripheral internally for RISC-V devices, and the
/// built-in Xtensa timer for Xtensa devices.
/// Delay driver, using [`Instant`].
#[derive(Clone, Copy, Default)]
#[non_exhaustive]
pub struct Delay;
@ -55,40 +51,24 @@ impl Delay {
}
/// Delay for the specified time
pub fn delay(&self, delay: MicrosDurationU64) {
let start = crate::time::now();
pub fn delay(&self, delay: Duration) {
let start = Instant::now();
while elapsed_since(start) < delay {}
while start.elapsed() < delay {}
}
/// Delay for the specified number of milliseconds
pub fn delay_millis(&self, ms: u32) {
for _ in 0..ms {
self.delay_micros(1000);
}
self.delay(Duration::from_millis(ms as u64));
}
/// Delay for the specified number of microseconds
pub fn delay_micros(&self, us: u32) {
let delay = MicrosDurationU64::micros(us as u64);
self.delay(delay);
self.delay(Duration::from_micros(us as u64));
}
/// Delay for the specified number of nanoseconds
pub fn delay_nanos(&self, ns: u32) {
let delay = MicrosDurationU64::nanos(ns as u64);
self.delay(delay);
}
}
fn elapsed_since(start: fugit::Instant<u64, 1, 1_000_000>) -> MicrosDurationU64 {
let now = crate::time::now();
if start.ticks() <= now.ticks() {
now - start
} else {
// now specifies at least 7 happy years, let's ignore this issue for
// now.
panic!("Time has wrapped around, which we currently don't handle");
self.delay(Duration::from_micros(ns.div_ceil(1000) as u64));
}
}

View File

@ -28,8 +28,8 @@
//!
//! let mut spi = Spi::new(
//! peripherals.SPI2,
//! Config::default().with_frequency(100.kHz()).with_mode(Mode::_0)
//! )?
//! Config::default().with_frequency(Rate::from_khz(100)).
//! with_mode(Mode::_0) )?
//! .with_sck(sclk)
//! .with_mosi(mosi)
//! .with_miso(miso)

View File

@ -68,12 +68,12 @@
//! # use esp_hal::gpio::Level;
//! # use esp_hal::timer::systimer::{etm::Event, SystemTimer};
//! # use esp_hal::timer::PeriodicTimer;
//! # use fugit::ExtU32;
//! use esp_hal::time::Duration;
//!
//! let syst = SystemTimer::new(peripherals.SYSTIMER);
//! let mut alarm0 = syst.alarm0;
//! let mut timer = PeriodicTimer::new(&mut alarm0);
//! timer.start(1u64.secs());
//! timer.start(Duration::from_secs(1));
//!
//! let mut led = peripherals.GPIO1;
//!

View File

@ -1,10 +1,9 @@
//! Low-power I2C driver
use fugit::HertzU32;
use crate::{
gpio::lp_io::LowPowerOutputOpenDrain,
peripherals::{LPWR, LP_AON, LP_I2C0, LP_IO, LP_PERI},
time::Rate,
};
const LP_I2C_FILTER_CYC_NUM_DEF: u8 = 7;
@ -89,7 +88,7 @@ impl LpI2c {
i2c: LP_I2C0,
_sda: LowPowerOutputOpenDrain<'_, 6>,
_scl: LowPowerOutputOpenDrain<'_, 7>,
frequency: HertzU32,
frequency: Rate,
) -> Self {
let me = Self { i2c };
@ -201,7 +200,7 @@ impl LpI2c {
// call
let source_clk = 16_000_000;
let bus_freq = frequency.raw();
let bus_freq = frequency.as_hz();
let clkm_div: u32 = source_clk / (bus_freq * 1024) + 1;
let sclk_freq: u32 = source_clk / clkm_div;

View File

@ -29,7 +29,6 @@ use core::{
use embedded_hal::i2c::Operation as EhalOperation;
use enumset::{EnumSet, EnumSetType};
use fugit::HertzU32;
use crate::{
asynch::AtomicWaker,
@ -47,6 +46,7 @@ use crate::{
peripherals::Interrupt,
private,
system::{PeripheralClockControl, PeripheralGuard},
time::Rate,
Async,
Blocking,
DriverMode,
@ -389,29 +389,21 @@ impl From<Ack> for u32 {
}
/// I2C driver configuration
#[derive(Debug, Clone, Copy, PartialEq, Eq, procmacros::BuilderLite)]
#[derive(Debug, Clone, Copy, PartialEq, Eq, Hash, procmacros::BuilderLite)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
#[non_exhaustive]
pub struct Config {
/// The I2C clock frequency.
frequency: HertzU32,
frequency: Rate,
/// I2C SCL timeout period.
timeout: BusTimeout,
}
impl core::hash::Hash for Config {
fn hash<H: core::hash::Hasher>(&self, state: &mut H) {
self.frequency.to_Hz().hash(state); // `HertzU32` doesn't implement `Hash`
self.timeout.hash(state);
}
}
impl Default for Config {
fn default() -> Self {
use fugit::RateExtU32;
Config {
frequency: 100.kHz(),
frequency: Rate::from_khz(100),
timeout: BusTimeout::BusCycles(10),
}
}
@ -1441,8 +1433,8 @@ impl Driver<'_> {
/// i2c_ll_set_bus_timing in ESP-IDF
fn set_frequency(&self, clock_config: &Config, timeout: BusTimeout) -> Result<(), ConfigError> {
let clocks = Clocks::get();
let source_clk = clocks.i2c_clock.raw();
let bus_freq = clock_config.frequency.raw();
let source_clk = clocks.i2c_clock.as_hz();
let bus_freq = clock_config.frequency.as_hz();
let half_cycle: u32 = source_clk / bus_freq / 2;
let scl_low = half_cycle;
@ -1519,8 +1511,8 @@ impl Driver<'_> {
/// i2c_ll_set_bus_timing in ESP-IDF
fn set_frequency(&self, clock_config: &Config, timeout: BusTimeout) -> Result<(), ConfigError> {
let clocks = Clocks::get();
let source_clk = clocks.apb_clock.raw();
let bus_freq = clock_config.frequency.raw();
let source_clk = clocks.apb_clock.as_hz();
let bus_freq = clock_config.frequency.as_hz();
let half_cycle: u32 = source_clk / bus_freq / 2;
// SCL
@ -1577,8 +1569,8 @@ impl Driver<'_> {
/// i2c_ll_set_bus_timing in ESP-IDF
fn set_frequency(&self, clock_config: &Config, timeout: BusTimeout) -> Result<(), ConfigError> {
let clocks = Clocks::get();
let source_clk = clocks.xtal_clock.raw();
let bus_freq = clock_config.frequency.raw();
let source_clk = clocks.xtal_clock.as_hz();
let bus_freq = clock_config.frequency.as_hz();
let clkm_div: u32 = source_clk / (bus_freq * 1024) + 1;
let sclk_freq: u32 = source_clk / clkm_div;

View File

@ -43,7 +43,7 @@
//! peripherals.I2S0,
//! Standard::Philips,
//! DataFormat::Data16Channel16,
//! 44100.Hz(),
//! Rate::from_hz(44100),
//! dma_channel,
//! rx_descriptors,
//! tx_descriptors,
@ -101,6 +101,7 @@ use crate::{
interrupt::{InterruptConfigurable, InterruptHandler},
peripheral::{Peripheral, PeripheralRef},
system::PeripheralGuard,
time::Rate,
Async,
Blocking,
DriverMode,
@ -332,7 +333,7 @@ impl<'d> I2s<'d, Blocking> {
i2s: impl Peripheral<P = impl RegisterAccess> + 'd,
standard: Standard,
data_format: DataFormat,
sample_rate: impl Into<fugit::HertzU32>,
sample_rate: Rate,
channel: impl Peripheral<P = CH> + 'd,
rx_descriptors: &'static mut [DmaDescriptor],
tx_descriptors: &'static mut [DmaDescriptor],
@ -681,7 +682,6 @@ impl<T> RegisterAccess for T where T: RegisterAccessPrivate {}
mod private {
use enumset::EnumSet;
use fugit::HertzU32;
use super::*;
#[cfg(not(i2s1))]
@ -1744,11 +1744,7 @@ mod private {
numerator: u32,
}
pub fn calculate_clock(
sample_rate: impl Into<fugit::HertzU32>,
channels: u8,
data_bits: u8,
) -> I2sClockDividers {
pub fn calculate_clock(sample_rate: Rate, channels: u8, data_bits: u8) -> I2sClockDividers {
// this loosely corresponds to `i2s_std_calculate_clock` and
// `i2s_ll_tx_set_mclk` in esp-idf
//
@ -1759,8 +1755,7 @@ mod private {
let mclk_multiple = if data_bits == 24 { 192 } else { 256 };
let sclk = crate::soc::constants::I2S_SCLK; // for now it's fixed 160MHz and 96MHz (just H2)
let rate_hz: HertzU32 = sample_rate.into();
let rate = rate_hz.raw();
let rate = sample_rate.as_hz();
let bclk = rate * channels as u32 * data_bits as u32;
let mclk = rate * mclk_multiple;

View File

@ -66,7 +66,7 @@
//! let mut parallel = I2sParallel::new(
//! i2s,
//! dma_channel,
//! 1.MHz(),
//! Rate::from_mhz(1),
//! pins,
//! clock,
//! ).into_async();
@ -102,8 +102,6 @@ use core::{
ops::{Deref, DerefMut},
};
use fugit::HertzU32;
use crate::{
dma::{
asynch::DmaTxFuture,
@ -125,6 +123,7 @@ use crate::{
peripheral::{Peripheral, PeripheralRef},
peripherals::{I2S0, I2S1},
system::PeripheralGuard,
time::Rate,
Async,
Blocking,
DriverMode,
@ -249,7 +248,7 @@ impl<'d> I2sParallel<'d, Blocking> {
pub fn new<CH>(
i2s: impl Peripheral<P = impl Instance> + 'd,
channel: impl Peripheral<P = CH> + 'd,
frequency: impl Into<fugit::HertzU32>,
frequency: Rate,
mut pins: impl TxPins<'d>,
clock_pin: impl Peripheral<P = impl PeripheralOutput> + 'd,
) -> Self
@ -421,7 +420,7 @@ pub struct I2sClockDividers {
pub numerator: u32,
}
fn calculate_clock(sample_rate: impl Into<fugit::HertzU32>, data_bits: u8) -> I2sClockDividers {
fn calculate_clock(sample_rate: Rate, data_bits: u8) -> I2sClockDividers {
// this loosely corresponds to `i2s_std_calculate_clock` and
// `i2s_ll_tx_set_mclk` in esp-idf
//
@ -430,8 +429,7 @@ fn calculate_clock(sample_rate: impl Into<fugit::HertzU32>, data_bits: u8) -> I2
let sclk = crate::soc::constants::I2S_SCLK; // for now it's fixed 160MHz and 96MHz (just H2)
let rate_hz: HertzU32 = sample_rate.into();
let rate = rate_hz.raw();
let rate = sample_rate.as_hz();
let mclk = rate * 2;
let bclk_divider: u32 = if data_bits == 8 { 2 } else { 1 };
@ -600,9 +598,7 @@ pub trait Instance: Peripheral<P = Self> + DmaEligible + Into<AnyI2s> + 'static
});
}
fn setup(&self, frequency: impl Into<fugit::HertzU32>, bits: u8) {
let frequency: HertzU32 = frequency.into();
fn setup(&self, frequency: Rate, bits: u8) {
self.set_clock(calculate_clock(frequency, bits));
// Initialize I2S dev

View File

@ -17,7 +17,6 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::lcd_cam::{cam::{Camera, Config, RxEightBits}, LcdCam};
//! # use fugit::RateExtU32;
//! # use esp_hal::dma_rx_stream_buffer;
//!
//! # let dma_buf = dma_rx_stream_buffer!(20 * 1000, 1000);
@ -37,7 +36,7 @@
//! peripherals.GPIO16,
//! );
//!
//! let config = Config::default().with_frequency(20.MHz());
//! let config = Config::default().with_frequency(Rate::from_mhz(20));
//!
//! let lcd_cam = LcdCam::new(peripherals.LCD_CAM);
//! let mut camera = Camera::new(
@ -61,8 +60,6 @@ use core::{
ops::{Deref, DerefMut},
};
use fugit::{HertzU32, RateExtU32};
use crate::{
clock::Clocks,
dma::{ChannelRx, DmaError, DmaPeripheral, DmaRxBuffer, PeripheralRxChannel, Rx, RxChannelFor},
@ -77,6 +74,7 @@ use crate::{
peripheral::{Peripheral, PeripheralRef},
peripherals::LCD_CAM,
system::{self, GenericPeripheralGuard},
time::Rate,
Blocking,
};
@ -171,11 +169,11 @@ impl<'d> Camera<'d> {
pub fn apply_config(&mut self, config: &Config) -> Result<(), ConfigError> {
let clocks = Clocks::get();
let (i, divider) = calculate_clkm(
config.frequency.to_Hz() as _,
config.frequency.as_hz() as _,
&[
clocks.xtal_clock.to_Hz() as _,
clocks.cpu_clock.to_Hz() as _,
clocks.crypto_pwm_clock.to_Hz() as _,
clocks.xtal_clock.as_hz() as _,
clocks.cpu_clock.as_hz() as _,
clocks.crypto_pwm_clock.as_hz() as _,
],
)
.map_err(ConfigError::Clock)?;
@ -603,7 +601,7 @@ pub trait RxPins {
/// Configuration settings for the Camera interface.
pub struct Config {
/// The pixel clock frequency for the camera interface.
frequency: HertzU32,
frequency: Rate,
/// The byte order for the camera data.
byte_order: ByteOrder,
@ -618,7 +616,7 @@ pub struct Config {
impl Default for Config {
fn default() -> Self {
Self {
frequency: 20.MHz(),
frequency: Rate::from_mhz(20),
byte_order: Default::default(),
bit_order: Default::default(),
vsync_filter_threshold: None,

View File

@ -31,7 +31,7 @@
//! let lcd_cam = LcdCam::new(peripherals.LCD_CAM);
//!
//! let config = dpi::Config::default()
//! .with_frequency(1.MHz())
//! .with_frequency(Rate::from_mhz(1))
//! .with_clock_mode(ClockMode {
//! polarity: Polarity::IdleLow,
//! phase: Phase::ShiftLow,
@ -101,8 +101,6 @@ use core::{
ops::{Deref, DerefMut},
};
use fugit::{HertzU32, RateExtU32};
use crate::{
clock::Clocks,
dma::{ChannelTx, DmaError, DmaPeripheral, DmaTxBuffer, PeripheralTxChannel, Tx, TxChannelFor},
@ -118,6 +116,7 @@ use crate::{
peripheral::{Peripheral, PeripheralRef},
peripherals::LCD_CAM,
system::{self, GenericPeripheralGuard},
time::Rate,
Blocking,
DriverMode,
};
@ -176,11 +175,11 @@ where
// the LCD_PCLK divider must be at least 2. To make up for this the user
// provided frequency is doubled to match.
let (i, divider) = calculate_clkm(
(config.frequency.to_Hz() * 2) as _,
(config.frequency.as_hz() * 2) as _,
&[
clocks.xtal_clock.to_Hz() as _,
clocks.cpu_clock.to_Hz() as _,
clocks.crypto_pwm_clock.to_Hz() as _,
clocks.xtal_clock.as_hz() as _,
clocks.cpu_clock.as_hz() as _,
clocks.crypto_pwm_clock.as_hz() as _,
],
)
.map_err(ConfigError::Clock)?;
@ -702,7 +701,7 @@ pub struct Config {
clock_mode: ClockMode,
/// The frequency of the pixel clock.
frequency: HertzU32,
frequency: Rate,
/// Format of the byte data sent out.
format: Format,
@ -741,7 +740,7 @@ impl Default for Config {
fn default() -> Self {
Config {
clock_mode: Default::default(),
frequency: 1.MHz(),
frequency: Rate::from_mhz(1),
format: Default::default(),
timing: Default::default(),
vsync_idle_level: Level::Low,

View File

@ -33,7 +33,7 @@
//! );
//! let lcd_cam = LcdCam::new(peripherals.LCD_CAM);
//!
//! let config = Config::default().with_frequency(20.MHz());
//! let config = Config::default().with_frequency(Rate::from_mhz(20));
//!
//! let mut i8080 = I8080::new(
//! lcd_cam.lcd,
@ -57,8 +57,6 @@ use core::{
ops::{Deref, DerefMut},
};
use fugit::{HertzU32, RateExtU32};
use crate::{
clock::Clocks,
dma::{ChannelTx, DmaError, DmaPeripheral, DmaTxBuffer, PeripheralTxChannel, Tx, TxChannelFor},
@ -80,6 +78,7 @@ use crate::{
peripheral::{Peripheral, PeripheralRef},
peripherals::LCD_CAM,
system::{self, GenericPeripheralGuard},
time::Rate,
Blocking,
DriverMode,
};
@ -141,11 +140,11 @@ where
// the LCD_PCLK divider must be at least 2. To make up for this the user
// provided frequency is doubled to match.
let (i, divider) = calculate_clkm(
(config.frequency.to_Hz() * 2) as _,
(config.frequency.as_hz() * 2) as _,
&[
clocks.xtal_clock.to_Hz() as _,
clocks.cpu_clock.to_Hz() as _,
clocks.crypto_pwm_clock.to_Hz() as _,
clocks.xtal_clock.as_hz() as _,
clocks.cpu_clock.as_hz() as _,
clocks.crypto_pwm_clock.as_hz() as _,
],
)
.map_err(ConfigError::Clock)?;
@ -547,7 +546,7 @@ pub struct Config {
clock_mode: ClockMode,
/// The frequency of the pixel clock.
frequency: HertzU32,
frequency: Rate,
/// Setup cycles expected, must be at least 1. (6 bits)
setup_cycles: usize,
@ -574,7 +573,7 @@ impl Default for Config {
fn default() -> Self {
Self {
clock_mode: Default::default(),
frequency: 20.MHz(),
frequency: Rate::from_mhz(20),
setup_cycles: 1,
hold_cycles: 1,
cd_idle_edge: false,

View File

@ -41,7 +41,7 @@
//! .configure(timer::config::Config {
//! duty: timer::config::Duty::Duty5Bit,
//! clock_source: timer::LSClockSource::APBClk,
//! frequency: 24.kHz(),
//! frequency: Rate::from_khz(24),
//! })?;
//!
//! let mut channel0 = ledc.channel(channel::Number::Channel0, led);

View File

@ -11,12 +11,10 @@
//!
//! LEDC uses APB as clock source.
use fugit::HertzU32;
#[cfg(esp32)]
use super::HighSpeed;
use super::{LowSpeed, Speed};
use crate::{clock::Clocks, pac};
use crate::{clock::Clocks, pac, time::Rate};
const LEDC_TIMER_DIV_NUM_MAX: u64 = 0x3FFFF;
@ -63,7 +61,7 @@ pub enum Number {
/// Timer configuration
pub mod config {
use fugit::HertzU32;
use crate::time::Rate;
/// Number of bits reserved for duty cycle adjustment
#[derive(PartialEq, Eq, Copy, Clone, Debug)]
@ -162,7 +160,7 @@ pub mod config {
/// The clock source for the timer.
pub clock_source: CS,
/// The frequency of the PWM signal in Hertz.
pub frequency: HertzU32,
pub frequency: Rate,
}
}
@ -188,7 +186,7 @@ impl TimerSpeed for HighSpeed {
/// Interface for Timers
pub trait TimerIFace<S: TimerSpeed> {
/// Return the frequency of the timer
fn freq(&self) -> Option<HertzU32>;
fn freq(&self) -> Option<Rate>;
/// Configure the timer
fn configure(&mut self, config: config::Config<S::ClockSourceType>) -> Result<(), Error>;
@ -209,7 +207,7 @@ pub trait TimerIFace<S: TimerSpeed> {
/// Interface for HW configuration of timer
pub trait TimerHW<S: TimerSpeed> {
/// Get the current source timer frequency from the HW
fn freq_hw(&self) -> Option<HertzU32>;
fn freq_hw(&self) -> Option<Rate>;
/// Configure the HW for the timer
fn configure_hw(&self, divisor: u32);
@ -234,7 +232,7 @@ where
Timer<'a, S>: TimerHW<S>,
{
/// Return the frequency of the timer
fn freq(&self) -> Option<HertzU32> {
fn freq(&self) -> Option<Rate> {
self.freq_hw()
}
@ -244,9 +242,9 @@ where
self.clock_source = Some(config.clock_source);
// TODO: we should return some error here if `unwrap()` fails
let src_freq: u32 = self.freq().unwrap().to_Hz();
let src_freq: u32 = self.freq().unwrap().as_hz();
let precision = 1 << config.duty as u32;
let frequency: u32 = config.frequency.raw();
let frequency: u32 = config.frequency.as_hz();
self.frequency = frequency;
let mut divisor = ((src_freq as u64) << 8) / frequency as u64 / precision as u64;
@ -309,7 +307,7 @@ impl<'a, S: TimerSpeed> Timer<'a, S> {
/// Timer HW implementation for LowSpeed timers
impl TimerHW<LowSpeed> for Timer<'_, LowSpeed> {
/// Get the current source timer frequency from the HW
fn freq_hw(&self) -> Option<HertzU32> {
fn freq_hw(&self) -> Option<Rate> {
self.clock_source.map(|source| match source {
LSClockSource::APBClk => {
let clocks = Clocks::get();
@ -372,7 +370,7 @@ impl TimerHW<LowSpeed> for Timer<'_, LowSpeed> {
/// Timer HW implementation for HighSpeed timers
impl TimerHW<HighSpeed> for Timer<'_, HighSpeed> {
/// Get the current source timer frequency from the HW
fn freq_hw(&self) -> Option<HertzU32> {
fn freq_hw(&self) -> Option<Rate> {
self.clock_source.map(|source| match source {
HSClockSource::APBClk => {
let clocks = Clocks::get();

View File

@ -186,6 +186,7 @@ pub mod peripheral;
mod reg_access;
#[cfg(any(spi0, spi1, spi2, spi3))]
pub mod spi;
pub mod time;
#[cfg(any(uart0, uart1, uart2))]
pub mod uart;
@ -278,7 +279,6 @@ unstable_module! {
pub mod sync;
#[cfg(any(dport, hp_sys, pcr, system))]
pub mod system;
pub mod time;
#[cfg(any(systimer, timg0, timg1))]
pub mod timer;
#[cfg(touch)]

View File

@ -11,7 +11,7 @@ macro_rules! before_snippet {
r#"
# #![no_std]
# use procmacros::handler;
# use esp_hal::{interrupt::{self, InterruptConfigurable}, time::{RateExtU32 as _, ExtU64 as _}};
# use esp_hal::{interrupt::{self, InterruptConfigurable}, time::{Duration, Instant, Rate}};
# macro_rules! println {
# ($($tt:tt)*) => { };
# }

View File

@ -57,11 +57,11 @@
//! // initialize peripheral
#![cfg_attr(
esp32h2,
doc = "let clock_cfg = PeripheralClockConfig::with_frequency(40.MHz())?;"
doc = "let clock_cfg = PeripheralClockConfig::with_frequency(Rate::from_mhz(40))?;"
)]
#![cfg_attr(
not(esp32h2),
doc = "let clock_cfg = PeripheralClockConfig::with_frequency(32.MHz())?;"
doc = "let clock_cfg = PeripheralClockConfig::with_frequency(Rate::from_mhz(32))?;"
)]
//! let mut mcpwm = McPwm::new(peripherals.MCPWM0, clock_cfg);
//!
@ -75,8 +75,8 @@
//! // 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())?;
//! mcpwm.timer0.start(timer_clock_cfg);
//! .timer_clock_with_frequency(99, PwmWorkingMode::Increase,
//! Rate::from_khz(20))?; mcpwm.timer0.start(timer_clock_cfg);
//!
//! // pin will be high 50% of the time
//! pwm_pin.set_timestamp(50);
@ -84,7 +84,6 @@
//! # }
//! ```
use fugit::HertzU32;
use operator::Operator;
use timer::Timer;
@ -94,6 +93,7 @@ use crate::{
pac,
peripheral::{Peripheral, PeripheralRef},
system::{self, PeripheralGuard},
time::Rate,
};
/// MCPWM operators
@ -190,7 +190,7 @@ impl<'d, PWM: PwmPeripheral> McPwm<'d, PWM> {
/// Clock configuration of the MCPWM peripheral
#[derive(Copy, Clone)]
pub struct PeripheralClockConfig {
frequency: HertzU32,
frequency: Rate,
prescaler: u8,
}
@ -236,7 +236,7 @@ impl PeripheralClockConfig {
/// Only divisors of the input clock (`160 Mhz / 1`, `160 Mhz / 2`, ...,
/// `160 Mhz / 256`) are representable exactly. Other target frequencies
/// will be rounded up to the next divisor.
pub fn with_frequency(target_freq: HertzU32) -> Result<Self, FrequencyError> {
pub fn with_frequency(target_freq: Rate) -> Result<Self, FrequencyError> {
let clocks = Clocks::get();
cfg_if::cfg_if! {
if #[cfg(esp32)] {
@ -250,7 +250,7 @@ impl PeripheralClockConfig {
}
}
if target_freq.raw() == 0 || target_freq > source_clock {
if target_freq.as_hz() == 0 || target_freq > source_clock {
return Err(FrequencyError);
}
@ -266,7 +266,7 @@ impl PeripheralClockConfig {
///
/// ### Note:
/// The actual value is rounded down to the nearest `u32` value
pub fn frequency(&self) -> HertzU32 {
pub fn frequency(&self) -> Rate {
self.frequency
}
@ -301,7 +301,7 @@ impl PeripheralClockConfig {
&self,
period: u16,
mode: timer::PwmWorkingMode,
target_freq: HertzU32,
target_freq: Rate,
) -> Result<timer::TimerClockConfig, FrequencyError> {
timer::TimerClockConfig::with_frequency(self, period, mode, target_freq)
}

View File

@ -463,11 +463,11 @@ impl<PWM: PwmPeripheral, const OP: u8, const IS_A: bool> embedded_hal::pwm::SetD
/// true);
#[cfg_attr(
esp32h2,
doc = "let clock_cfg = PeripheralClockConfig::with_frequency(40.MHz())?;"
doc = "let clock_cfg = PeripheralClockConfig::with_frequency(Rate::from_mhz(40))?;"
)]
#[cfg_attr(
not(esp32h2),
doc = "let clock_cfg = PeripheralClockConfig::with_frequency(32.MHz())?;"
doc = "let clock_cfg = PeripheralClockConfig::with_frequency(Rate::from_mhz(32))?;"
)]
/// let mut mcpwm = McPwm::new(peripherals.MCPWM0, clock_cfg);
///

View File

@ -6,12 +6,11 @@
use core::marker::PhantomData;
use fugit::HertzU32;
use super::PeripheralGuard;
use crate::{
mcpwm::{FrequencyError, PeripheralClockConfig, PwmPeripheral},
pac,
time::Rate,
};
/// A MCPWM timer
@ -120,7 +119,7 @@ impl<const TIM: u8, PWM: PwmPeripheral> Timer<TIM, PWM> {
/// [`PeripheralClockConfig::timer_clock_with_frequency`](super::PeripheralClockConfig::timer_clock_with_frequency) to it.
#[derive(Copy, Clone)]
pub struct TimerClockConfig {
frequency: HertzU32,
frequency: Rate,
period: u16,
period_updating_method: PeriodUpdatingMethod,
prescaler: u8,
@ -154,7 +153,7 @@ impl TimerClockConfig {
clock: &PeripheralClockConfig,
period: u16,
mode: PwmWorkingMode,
target_freq: HertzU32,
target_freq: Rate,
) -> Result<Self, FrequencyError> {
let cycle_period = match mode {
PwmWorkingMode::Increase | PwmWorkingMode::Decrease => period as u32 + 1,
@ -162,13 +161,13 @@ impl TimerClockConfig {
PwmWorkingMode::UpDown => period as u32 * 2,
};
let target_timer_frequency = target_freq
.raw()
.as_hz()
.checked_mul(cycle_period)
.ok_or(FrequencyError)?;
if target_timer_frequency == 0 || target_freq > clock.frequency {
return Err(FrequencyError);
}
let prescaler = clock.frequency.raw() / target_timer_frequency - 1;
let prescaler = clock.frequency.as_hz() / target_timer_frequency - 1;
if prescaler > u8::MAX as u32 {
return Err(FrequencyError);
}
@ -195,7 +194,7 @@ impl TimerClockConfig {
///
/// ### Note:
/// The actual value is rounded down to the nearest `u32` value
pub fn frequency(&self) -> HertzU32 {
pub fn frequency(&self) -> Rate {
self.frequency
}
}

View File

@ -40,7 +40,7 @@
//! let parl_io = ParlIoRxOnly::new(
//! peripherals.PARL_IO,
//! dma_channel,
//! 1.MHz(),
//! Rate::from_mhz(1),
//! )?;
//!
//! let mut parl_io_rx = parl_io
@ -92,7 +92,7 @@
//! let parl_io = ParlIoTxOnly::new(
//! peripherals.PARL_IO,
//! dma_channel,
//! 1.MHz(),
//! Rate::from_mhz(1),
//! )?;
//!
//! let mut clock_pin = ClkOutPin::new(peripherals.GPIO6);
@ -125,7 +125,6 @@ use core::{
};
use enumset::{EnumSet, EnumSetType};
use fugit::HertzU32;
use peripheral::PeripheralRef;
use private::*;
@ -155,6 +154,7 @@ use crate::{
peripheral::{self, Peripheral},
peripherals::{Interrupt, PARL_IO, PCR},
system::{self, GenericPeripheralGuard},
time::Rate,
Async,
Blocking,
DriverMode,
@ -1083,7 +1083,7 @@ impl<'d> ParlIoFullDuplex<'d, Blocking> {
pub fn new<CH>(
_parl_io: impl Peripheral<P = PARL_IO> + 'd,
dma_channel: impl Peripheral<P = CH> + 'd,
frequency: HertzU32,
frequency: Rate,
) -> Result<Self, Error>
where
CH: DmaChannelFor<PARL_IO>,
@ -1225,7 +1225,7 @@ impl<'d> ParlIoTxOnly<'d, Blocking> {
pub fn new<CH>(
_parl_io: impl Peripheral<P = PARL_IO> + 'd,
dma_channel: impl Peripheral<P = CH> + 'd,
frequency: HertzU32,
frequency: Rate,
) -> Result<Self, Error>
where
CH: TxChannelFor<PARL_IO>,
@ -1353,7 +1353,7 @@ impl<'d> ParlIoRxOnly<'d, Blocking> {
pub fn new<CH>(
_parl_io: impl Peripheral<P = PARL_IO> + 'd,
dma_channel: impl Peripheral<P = CH> + 'd,
frequency: HertzU32,
frequency: Rate,
) -> Result<Self, Error>
where
CH: RxChannelFor<PARL_IO>,
@ -1466,12 +1466,12 @@ impl crate::interrupt::InterruptConfigurable for ParlIoRxOnly<'_, Blocking> {
}
}
fn internal_init(frequency: HertzU32) -> Result<(), Error> {
if frequency.raw() > 40_000_000 {
fn internal_init(frequency: Rate) -> Result<(), Error> {
if frequency.as_hz() > 40_000_000 {
return Err(Error::UnreachableClockRate);
}
let divider = crate::soc::constants::PARL_IO_SCLK / frequency.raw();
let divider = crate::soc::constants::PARL_IO_SCLK / frequency.as_hz();
if divider > 0xffff {
return Err(Error::UnreachableClockRate);
}

View File

@ -56,8 +56,8 @@
//! # use esp_hal::rmt::TxChannelConfig;
//! # use esp_hal::rmt::Rmt;
//! # use crate::esp_hal::rmt::TxChannelCreator;
#![cfg_attr(esp32h2, doc = "let freq = 32.MHz();")]
#![cfg_attr(not(esp32h2), doc = "let freq = 80.MHz();")]
#![cfg_attr(esp32h2, doc = "let freq = Rate::from_mhz(32);")]
#![cfg_attr(not(esp32h2), doc = "let freq = Rate::from_mhz(80);")]
//! let rmt = Rmt::new(peripherals.RMT, freq)?;
//! let mut channel = rmt
//! .channel0
@ -84,8 +84,8 @@
//! # use esp_hal::rmt::{PulseCode, Rmt, TxChannel, TxChannelConfig, TxChannelCreator};
//!
//! // Configure frequency based on chip type
#![cfg_attr(esp32h2, doc = "let freq = 32.MHz();")]
#![cfg_attr(not(esp32h2), doc = "let freq = 80.MHz();")]
#![cfg_attr(esp32h2, doc = "let freq = Rate::from_mhz(32);")]
#![cfg_attr(not(esp32h2), doc = "let freq = Rate::from_mhz(80);")]
//! let rmt = Rmt::new(peripherals.RMT, freq)?;
//!
//! let tx_config = TxChannelConfig::default().with_clk_divider(255);
@ -124,8 +124,8 @@
//! );
//!
//! // Configure frequency based on chip type
#![cfg_attr(esp32h2, doc = "let freq = 32.MHz();")]
#![cfg_attr(not(esp32h2), doc = "let freq = 80.MHz();")]
#![cfg_attr(esp32h2, doc = "let freq = Rate::from_mhz(32);")]
#![cfg_attr(not(esp32h2), doc = "let freq = Rate::from_mhz(80);")]
//! let rmt = Rmt::new(peripherals.RMT, freq)?;
//!
//! let rx_config = RxChannelConfig::default()
@ -227,7 +227,6 @@ use core::{
};
use enumset::{EnumSet, EnumSetType};
use fugit::HertzU32;
use crate::{
asynch::AtomicWaker,
@ -240,6 +239,7 @@ use crate::{
peripherals::{Interrupt, RMT},
soc::constants,
system::{self, GenericPeripheralGuard},
time::Rate,
Async,
Blocking,
};
@ -393,7 +393,7 @@ where
{
pub(crate) fn new_internal(
peripheral: impl Peripheral<P = RMT> + 'd,
frequency: HertzU32,
frequency: Rate,
) -> Result<Self, Error> {
let me = Rmt::create(peripheral);
me.configure_clock(frequency)?;
@ -401,8 +401,8 @@ where
}
#[cfg(any(esp32, esp32s2))]
fn configure_clock(&self, frequency: HertzU32) -> Result<(), Error> {
if frequency != HertzU32::MHz(80) {
fn configure_clock(&self, frequency: Rate) -> Result<(), Error> {
if frequency != Rate::from_mhz(80) {
return Err(Error::UnreachableTargetFrequency);
}
@ -412,7 +412,7 @@ where
}
#[cfg(not(any(esp32, esp32s2)))]
fn configure_clock(&self, frequency: HertzU32) -> Result<(), Error> {
fn configure_clock(&self, frequency: Rate) -> Result<(), Error> {
let src_clock = crate::soc::constants::RMT_CLOCK_SRC_FREQ;
if frequency > src_clock {
@ -433,10 +433,7 @@ where
impl<'d> Rmt<'d, Blocking> {
/// Create a new RMT instance
pub fn new(
peripheral: impl Peripheral<P = RMT> + 'd,
frequency: HertzU32,
) -> Result<Self, Error> {
pub fn new(peripheral: impl Peripheral<P = RMT> + 'd, frequency: Rate) -> Result<Self, Error> {
Self::new_internal(peripheral, frequency)
}

View File

@ -55,7 +55,7 @@
//! let mut rtc = Rtc::new(peripherals.LPWR);
//!
//! rtc.set_interrupt_handler(interrupt_handler);
//! rtc.rwdt.set_timeout(RwdtStage::Stage0, 2000.millis());
//! rtc.rwdt.set_timeout(RwdtStage::Stage0, Duration::from_millis(2000));
//! rtc.rwdt.listen();
//!
//! critical_section::with(|cs| RWDT.borrow_ref_mut(cs).replace(rtc.rwdt));
@ -81,7 +81,10 @@
//!
//! println!("Restarting in 5 seconds...");
//!
//! rwdt.set_timeout(RwdtStage::Stage0, 5000u64.millis());
//! rwdt.set_timeout(
//! RwdtStage::Stage0,
//! Duration::from_millis(5000),
//! );
//! rwdt.unlisten();
//! }
//! });
@ -110,17 +113,12 @@
//! ```
use chrono::{DateTime, NaiveDateTime};
#[cfg(not(any(esp32c6, esp32h2)))]
use fugit::HertzU32;
use fugit::MicrosDurationU64;
pub use self::rtc::SocResetReason;
#[cfg(not(any(esp32c6, esp32h2)))]
use crate::clock::XtalClock;
#[cfg(not(esp32))]
use crate::efuse::Efuse;
#[cfg(not(any(esp32c6, esp32h2)))]
use crate::peripherals::{LPWR, TIMG0};
#[cfg(any(esp32, esp32s3, esp32c3, esp32c6, esp32c2))]
use crate::rtc_cntl::sleep::{RtcSleepConfig, WakeSource, WakeTriggers};
use crate::{
@ -129,8 +127,14 @@ use crate::{
peripheral::{Peripheral, PeripheralRef},
peripherals::Interrupt,
reset::{SleepSource, WakeupReason},
time::Duration,
Cpu,
};
#[cfg(not(any(esp32c6, esp32h2)))]
use crate::{
peripherals::{LPWR, TIMG0},
time::Rate,
};
// only include sleep where it's been implemented
#[cfg(any(esp32, esp32s3, esp32c3, esp32c6, esp32c2))]
pub mod sleep;
@ -171,13 +175,13 @@ pub(crate) enum RtcFastClock {
#[cfg(not(any(esp32c6, esp32h2)))]
impl Clock for RtcFastClock {
fn frequency(&self) -> HertzU32 {
fn frequency(&self) -> Rate {
match self {
RtcFastClock::RtcFastClockXtalD4 => HertzU32::Hz(40_000_000 / 4),
RtcFastClock::RtcFastClockXtalD4 => Rate::from_hz(40_000_000 / 4),
#[cfg(any(esp32, esp32s2))]
RtcFastClock::RtcFastClock8m => HertzU32::Hz(8_500_000),
RtcFastClock::RtcFastClock8m => Rate::from_hz(8_500_000),
#[cfg(any(esp32c2, esp32c3, esp32c6, esp32h2, esp32s3))]
RtcFastClock::RtcFastClock8m => HertzU32::Hz(17_500_000),
RtcFastClock::RtcFastClock8m => Rate::from_hz(17_500_000),
}
}
}
@ -199,19 +203,19 @@ pub enum RtcSlowClock {
#[cfg(not(any(esp32c6, esp32h2)))]
impl Clock for RtcSlowClock {
fn frequency(&self) -> HertzU32 {
fn frequency(&self) -> Rate {
match self {
#[cfg(esp32)]
RtcSlowClock::RtcSlowClockRtc => HertzU32::Hz(150_000),
RtcSlowClock::RtcSlowClockRtc => Rate::from_hz(150_000),
#[cfg(esp32s2)]
RtcSlowClock::RtcSlowClockRtc => HertzU32::Hz(90_000),
RtcSlowClock::RtcSlowClockRtc => Rate::from_hz(90_000),
#[cfg(any(esp32c2, esp32c3, esp32s3))]
RtcSlowClock::RtcSlowClockRtc => HertzU32::Hz(136_000),
RtcSlowClock::RtcSlowClock32kXtal => HertzU32::Hz(32_768),
RtcSlowClock::RtcSlowClockRtc => Rate::from_hz(136_000),
RtcSlowClock::RtcSlowClock32kXtal => Rate::from_hz(32_768),
#[cfg(any(esp32, esp32s2))]
RtcSlowClock::RtcSlowClock8mD256 => HertzU32::Hz(8_500_000 / 256),
RtcSlowClock::RtcSlowClock8mD256 => Rate::from_hz(8_500_000 / 256),
#[cfg(any(esp32c2, esp32c3, esp32s3))]
RtcSlowClock::RtcSlowClock8mD256 => HertzU32::Hz(17_500_000 / 256),
RtcSlowClock::RtcSlowClock8mD256 => Rate::from_hz(17_500_000 / 256),
}
}
}
@ -307,10 +311,10 @@ impl<'d> Rtc<'d> {
}
/// Get the time since boot.
pub fn time_since_boot(&self) -> MicrosDurationU64 {
MicrosDurationU64::micros(
pub fn time_since_boot(&self) -> Duration {
Duration::from_micros(
self.time_since_boot_raw() * 1_000_000
/ RtcClock::slow_freq().frequency().to_Hz() as u64,
/ RtcClock::slow_freq().frequency().as_hz() as u64,
)
}
@ -360,7 +364,7 @@ impl<'d> Rtc<'d> {
pub fn current_time(&self) -> NaiveDateTime {
// Current time is boot time + time since boot
let rtc_time_us = self.time_since_boot().to_micros();
let rtc_time_us = self.time_since_boot().as_micros();
let boot_time_us = self.boot_time_us();
let wrapped_boot_time_us = u64::MAX - boot_time_us;
@ -394,7 +398,7 @@ impl<'d> Rtc<'d> {
// Current time is boot time + time since boot (rtc time)
// So boot time = current time - time since boot (rtc time)
let rtc_time_us = self.time_since_boot().to_micros();
let rtc_time_us = self.time_since_boot().as_micros();
if current_time_us < rtc_time_us {
// An overflow would happen if we subtracted rtc_time_us from current_time_us.
// To work around this, we can wrap around u64::MAX by subtracting the
@ -708,7 +712,7 @@ impl RtcClock {
}
};
let us_time_estimate = HertzU32::MHz(slowclk_cycles) / expected_freq.frequency();
let us_time_estimate = Rate::from_mhz(slowclk_cycles) / expected_freq.frequency();
// Start calibration
timg0
@ -997,10 +1001,10 @@ impl Rwdt {
}
/// Configure timeout value in ms for the selected stage.
pub fn set_timeout(&mut self, stage: RwdtStage, timeout: MicrosDurationU64) {
pub fn set_timeout(&mut self, stage: RwdtStage, timeout: Duration) {
let rtc_cntl = LP_WDT::regs();
let timeout_raw = (timeout.to_millis() * (RtcClock::cycles_to_1ms() as u64)) as u32;
let timeout_raw = (timeout.as_millis() * (RtcClock::cycles_to_1ms() as u64)) as u32;
self.set_write_protection(false);
unsafe {

View File

@ -2,7 +2,6 @@
// on the same version until documentation is released and the code can be
// reasoned about.
use fugit::HertzU32;
use strum::FromRepr;
use crate::{
@ -24,6 +23,7 @@ use crate::{
rtc_cntl::RtcClock,
soc::efuse::Efuse,
system::RadioPeripherals,
time::Rate,
};
const I2C_DIG_REG: u8 = 0x6d;
@ -1359,13 +1359,13 @@ pub(crate) enum RtcFastClock {
}
impl Clock for RtcFastClock {
fn frequency(&self) -> HertzU32 {
fn frequency(&self) -> Rate {
match self {
RtcFastClock::RtcFastClockXtalD2 => {
// TODO: Is the value correct?
HertzU32::Hz(40_000_000 / 2)
Rate::from_hz(40_000_000 / 2)
}
RtcFastClock::RtcFastClockRcFast => HertzU32::Hz(17_500_000),
RtcFastClock::RtcFastClockRcFast => Rate::from_hz(17_500_000),
}
}
}
@ -1385,12 +1385,12 @@ pub enum RtcSlowClock {
}
impl Clock for RtcSlowClock {
fn frequency(&self) -> HertzU32 {
fn frequency(&self) -> Rate {
match self {
RtcSlowClock::RtcSlowClockRcSlow => HertzU32::Hz(136_000),
RtcSlowClock::RtcSlowClock32kXtal => HertzU32::Hz(32_768),
RtcSlowClock::RtcSlowClock32kRc => HertzU32::Hz(32_768),
RtcSlowClock::RtcSlowOscSlow => HertzU32::Hz(32_768),
RtcSlowClock::RtcSlowClockRcSlow => Rate::from_hz(136_000),
RtcSlowClock::RtcSlowClock32kXtal => Rate::from_hz(32_768),
RtcSlowClock::RtcSlowClock32kRc => Rate::from_hz(32_768),
RtcSlowClock::RtcSlowOscSlow => Rate::from_hz(32_768),
}
}
}
@ -1671,7 +1671,7 @@ impl RtcClock {
}
};
let us_time_estimate = (HertzU32::MHz(slowclk_cycles) / expected_freq).to_Hz();
let us_time_estimate = (Rate::from_mhz(slowclk_cycles) / expected_freq).as_hz();
// Start calibration
timg0
@ -1814,7 +1814,7 @@ impl RtcClock {
while timg0.rtccalicfg().read().rtc_cali_rdy().bit_is_clear() {}
(timg0.rtccalicfg1().read().rtc_cali_value().bits()
* (RtcSlowClock::RtcSlowClockRcSlow.frequency().to_Hz() / 100))
* (RtcSlowClock::RtcSlowClockRcSlow.frequency().as_hz() / 100))
/ 1_000_000
}
}

View File

@ -1,10 +1,10 @@
use fugit::HertzU32;
use strum::FromRepr;
use crate::{
clock::{clocks_ll::regi2c_write_mask, Clock, XtalClock},
peripherals::{LPWR, LP_AON, PCR, PMU, TIMG0},
rtc_cntl::RtcClock,
time::Rate,
};
const I2C_PMU: u8 = 0x6d;
@ -202,10 +202,10 @@ pub(crate) enum RtcFastClock {
}
impl Clock for RtcFastClock {
fn frequency(&self) -> HertzU32 {
fn frequency(&self) -> Rate {
match self {
RtcFastClock::RtcFastClockXtalD2 => HertzU32::Hz(16_000_000),
RtcFastClock::RtcFastClockRcFast => HertzU32::Hz(8_000_000),
RtcFastClock::RtcFastClockXtalD2 => Rate::from_hz(16_000_000),
RtcFastClock::RtcFastClockRcFast => Rate::from_hz(8_000_000),
}
}
}
@ -226,12 +226,12 @@ pub enum RtcSlowClock {
}
impl Clock for RtcSlowClock {
fn frequency(&self) -> HertzU32 {
fn frequency(&self) -> Rate {
match self {
RtcSlowClock::RtcSlowClockRcSlow => HertzU32::Hz(150_000),
RtcSlowClock::RtcSlowClock32kXtal => HertzU32::Hz(32_768),
RtcSlowClock::RtcSlowClock32kRc => HertzU32::Hz(32_768),
RtcSlowClock::RtcSlowOscSlow => HertzU32::Hz(32_768),
RtcSlowClock::RtcSlowClockRcSlow => Rate::from_hz(150_000),
RtcSlowClock::RtcSlowClock32kXtal => Rate::from_hz(32_768),
RtcSlowClock::RtcSlowClock32kRc => Rate::from_hz(32_768),
RtcSlowClock::RtcSlowOscSlow => Rate::from_hz(32_768),
}
}
}
@ -516,7 +516,7 @@ impl RtcClock {
}
};
let us_time_estimate = (HertzU32::MHz(slowclk_cycles) / expected_freq).to_Hz();
let us_time_estimate = (Rate::from_mhz(slowclk_cycles) / expected_freq).as_hz();
// Start calibration
timg0
@ -621,7 +621,7 @@ impl RtcClock {
while timg0.rtccalicfg().read().rtc_cali_rdy().bit_is_clear() {}
(timg0.rtccalicfg1().read().rtc_cali_value().bits()
* (RtcSlowClock::RtcSlowClockRcSlow.frequency().to_Hz() / 100))
* (RtcSlowClock::RtcSlowClockRcSlow.frequency().as_hz() / 100))
/ 1_000_000
}
}

View File

@ -79,7 +79,7 @@ impl WakeSource for TimerWakeupSource {
let clock_freq = RtcClock::slow_freq();
// TODO: maybe add sleep time adjustlemnt like idf
// TODO: maybe add check to prevent overflow?
let clock_hz = clock_freq.frequency().to_Hz() as u64;
let clock_hz = clock_freq.frequency().as_hz() as u64;
let ticks = self.duration.as_micros() as u64 * clock_hz / 1_000_000u64;
// "alarm" time in slow rtc ticks
let now = rtc.time_since_boot_raw();

View File

@ -134,7 +134,7 @@ impl WakeSource for TimerWakeupSource {
let clock_freq = RtcClock::slow_freq();
// TODO: maybe add sleep time adjustlemnt like idf
// TODO: maybe add check to prevent overflow?
let clock_hz = clock_freq.frequency().to_Hz() as u64;
let clock_hz = clock_freq.frequency().as_hz() as u64;
let ticks = self.duration.as_micros() as u64 * clock_hz / 1_000_000u64;
// "alarm" time in slow rtc ticks
let now = rtc.time_since_boot_raw();

View File

@ -133,7 +133,7 @@ impl WakeSource for TimerWakeupSource {
let clock_freq = RtcClock::slow_freq();
// TODO: maybe add sleep time adjustlemnt like idf
// TODO: maybe add check to prevent overflow?
let clock_hz = clock_freq.frequency().to_Hz() as u64;
let clock_hz = clock_freq.frequency().as_hz() as u64;
let ticks = self.duration.as_micros() as u64 * clock_hz / 1_000_000u64;
// "alarm" time in slow rtc ticks
let now = rtc.time_since_boot_raw();

View File

@ -41,7 +41,7 @@ impl WakeSource for TimerWakeupSource {
let clock_freq = RtcClock::slow_freq();
// TODO: maybe add sleep time adjustment like idf
// TODO: maybe add check to prevent overflow?
let clock_hz = clock_freq.frequency().to_Hz() as u64;
let clock_hz = clock_freq.frequency().as_hz() as u64;
let ticks = self.duration.as_micros() as u64 * clock_hz / 1_000_000u64;
// "alarm" time in slow rtc ticks
let now = rtc.time_since_boot_raw();

View File

@ -120,7 +120,7 @@ impl WakeSource for TimerWakeupSource {
let clock_freq = RtcClock::slow_freq();
// TODO: maybe add sleep time adjustlemnt like idf
// TODO: maybe add check to prevent overflow?
let clock_hz = clock_freq.frequency().to_Hz() as u64;
let clock_hz = clock_freq.frequency().as_hz() as u64;
let ticks = self.duration.as_micros() as u64 * clock_hz / 1_000_000u64;
// "alarm" time in slow rtc ticks
let now = rtc.time_since_boot_raw();

View File

@ -29,7 +29,7 @@
//! )?;
//!
//! loop {
//! delay.delay(1.secs());
//! delay.delay(Duration::from_secs(1));
//! let count = critical_section::with(|cs| *counter.borrow_ref(cs));
//! }
//! # }
@ -42,7 +42,7 @@
//! counter: &critical_section::Mutex<RefCell<i32>>,
//! ) -> ! {
//! loop {
//! delay.delay(500.millis());
//! delay.delay(Duration::from_millis(500));
//!
//! critical_section::with(|cs| {
//! let mut val = counter.borrow_ref_mut(cs);

View File

@ -47,10 +47,8 @@
//! # }
//! ```
use fugit::{HertzU32, RateExtU32};
pub use self::fields::*;
use crate::peripherals::EFUSE;
use crate::{peripherals::EFUSE, time::Rate};
mod fields;
@ -99,14 +97,14 @@ impl Efuse {
///
/// Note that the actual clock may be lower, depending on the current power
/// configuration of the chip, clock source, and other settings.
pub fn max_cpu_frequency() -> HertzU32 {
pub fn max_cpu_frequency() -> Rate {
let has_rating = Self::read_bit(CHIP_CPU_FREQ_RATED);
let has_low_rating = Self::read_bit(CHIP_CPU_FREQ_LOW);
if has_rating && has_low_rating {
160.MHz()
Rate::from_mhz(160)
} else {
240.MHz()
Rate::from_mhz(240)
}
}

View File

@ -38,6 +38,8 @@ macro_rules! trm_link {
pub use chip;
pub(crate) mod constants {
use crate::time::Rate;
/// The base clock frequency for the I2S peripheral (Hertz).
pub const I2S_SCLK: u32 = 160_000_000;
/// The default clock source for I2S operations.
@ -51,7 +53,7 @@ pub(crate) mod constants {
/// The upper bound of the system's DRAM (Data RAM) address space.
pub const SOC_DRAM_HIGH: usize = 0x4000_0000;
/// A reference clock tick of 1 MHz.
pub const REF_TICK: fugit::HertzU32 = fugit::HertzU32::MHz(1);
pub const REF_TICK: Rate = Rate::from_mhz(1);
}
/// Function initializes ESP32 specific memories (RTC slow and fast) and

View File

@ -36,11 +36,13 @@ pub(crate) mod registers {
}
pub(crate) mod constants {
use crate::time::Rate;
/// The lower bound of the system's DRAM (Data RAM) address space.
pub const SOC_DRAM_LOW: usize = 0x3FCA_0000;
/// The upper bound of the system's DRAM (Data RAM) address space.
pub const SOC_DRAM_HIGH: usize = 0x3FCE_0000;
/// RC FAST Clock value (Hertz).
pub const RC_FAST_CLK: fugit::HertzU32 = fugit::HertzU32::kHz(17500);
pub const RC_FAST_CLK: Rate = Rate::from_khz(17500);
}

View File

@ -40,6 +40,8 @@ pub(crate) mod registers {
}
pub(crate) mod constants {
use crate::time::Rate;
/// The base clock frequency for the I2S peripheral (Hertz).
pub const I2S_SCLK: u32 = 160_000_000;
/// The default clock source for I2S operations.
@ -52,7 +54,7 @@ pub(crate) mod constants {
/// RMT Clock source value.
pub const RMT_CLOCK_SRC: u8 = 1;
/// RMT Clock source frequency.
pub const RMT_CLOCK_SRC_FREQ: fugit::HertzU32 = fugit::HertzU32::MHz(80);
pub const RMT_CLOCK_SRC_FREQ: Rate = Rate::from_mhz(80);
/// The lower bound of the system's DRAM (Data RAM) address space.
pub const SOC_DRAM_LOW: usize = 0x3FC8_0000;
@ -60,5 +62,5 @@ pub(crate) mod constants {
pub const SOC_DRAM_HIGH: usize = 0x3FCE_0000;
/// RC FAST Clock value (Hertz).
pub const RC_FAST_CLK: fugit::HertzU32 = fugit::HertzU32::kHz(17500);
pub const RC_FAST_CLK: Rate = Rate::from_khz(17500);
}

View File

@ -42,6 +42,8 @@ pub(crate) mod registers {
}
pub(crate) mod constants {
use crate::time::Rate;
/// The default clock source for the timer group.
pub const TIMG_DEFAULT_CLK_SRC: u8 = 1;
@ -57,7 +59,7 @@ pub(crate) mod constants {
/// The default clock source for the RMT peripheral.
pub const RMT_CLOCK_SRC: u8 = 1;
/// The frequency of the RMT clock source in Hertz.
pub const RMT_CLOCK_SRC_FREQ: fugit::HertzU32 = fugit::HertzU32::MHz(80);
pub const RMT_CLOCK_SRC_FREQ: Rate = Rate::from_mhz(80);
/// The clock frequency for the Parallel IO peripheral in Hertz.
pub const PARL_IO_SCLK: u32 = 240_000_000;
@ -68,5 +70,5 @@ pub(crate) mod constants {
pub const SOC_DRAM_HIGH: usize = 0x4088_0000;
/// RC FAST Clock value (Hertz).
pub const RC_FAST_CLK: fugit::HertzU32 = fugit::HertzU32::kHz(17_500);
pub const RC_FAST_CLK: Rate = Rate::from_khz(17_500);
}

View File

@ -41,6 +41,8 @@ pub(crate) mod registers {
}
pub(crate) mod constants {
use crate::time::Rate;
/// Default clock source for the timer group (TIMG) peripheral.
pub const TIMG_DEFAULT_CLK_SRC: u8 = 2;
@ -56,7 +58,7 @@ pub(crate) mod constants {
/// Clock source for the RMT peripheral (false = default source).
pub const RMT_CLOCK_SRC: bool = false;
/// Frequency of the RMT clock source, in Hertz.
pub const RMT_CLOCK_SRC_FREQ: fugit::HertzU32 = fugit::HertzU32::MHz(32);
pub const RMT_CLOCK_SRC_FREQ: Rate = Rate::from_mhz(32);
/// System clock frequency for the parallel I/O (PARL IO) peripheral, in
/// Hertz.
@ -68,5 +70,5 @@ pub(crate) mod constants {
pub const SOC_DRAM_HIGH: usize = 0x4085_0000;
/// RC FAST Clock value (Hertz).
pub const RC_FAST_CLK: fugit::HertzU32 = fugit::HertzU32::kHz(17500);
pub const RC_FAST_CLK: Rate = Rate::from_khz(17500);
}

View File

@ -42,6 +42,8 @@ macro_rules! trm_link {
pub use chip;
pub(crate) mod constants {
use crate::time::Rate;
/// System clock frequency for the I2S peripheral, in Hertz.
pub const I2S_SCLK: u32 = 160_000_000;
/// Default clock source for the I2S peripheral.
@ -55,7 +57,7 @@ pub(crate) mod constants {
/// End address of the system's DRAM (high range).
pub const SOC_DRAM_HIGH: usize = 0x4000_0000;
/// Reference clock tick frequency, set to 1 MHz.
pub const REF_TICK: fugit::HertzU32 = fugit::HertzU32::MHz(1);
pub const REF_TICK: Rate = Rate::from_mhz(1);
}
/// Function initializes ESP32 specific memories (RTC slow and fast) and

View File

@ -29,7 +29,7 @@
//! )?;
//!
//! loop {
//! delay.delay(1.secs());
//! delay.delay(Duration::from_secs(1));
//! let count = critical_section::with(|cs| *counter.borrow_ref(cs));
//! }
//! # }
@ -43,7 +43,7 @@
//! counter: &critical_section::Mutex<RefCell<i32>>,
//! ) -> ! {
//! loop {
//! delay.delay(500.millis());
//! delay.delay(Duration::from_millis(500));
//!
//! critical_section::with(|cs| {
//! let mut val = counter.borrow_ref_mut(cs);

View File

@ -43,6 +43,8 @@ macro_rules! trm_link {
pub use chip;
pub(crate) mod constants {
use crate::time::Rate;
/// The base clock frequency for the I2S peripheral (Hertz).
pub const I2S_SCLK: u32 = 160_000_000;
/// The default clock source for I2S operations.
@ -55,7 +57,7 @@ pub(crate) mod constants {
/// RMT Clock source value.
pub const RMT_CLOCK_SRC: u8 = 1;
/// RMT Clock source frequency.
pub const RMT_CLOCK_SRC_FREQ: fugit::HertzU32 = fugit::HertzU32::MHz(80);
pub const RMT_CLOCK_SRC_FREQ: Rate = Rate::from_mhz(80);
/// The lower bound of the system's DRAM (Data RAM) address space.
pub const SOC_DRAM_LOW: usize = 0x3FC8_8000;
@ -63,7 +65,7 @@ pub(crate) mod constants {
pub const SOC_DRAM_HIGH: usize = 0x3FD0_0000;
/// A reference clock tick of 1 MHz.
pub const RC_FAST_CLK: fugit::HertzU32 = fugit::HertzU32::kHz(17500);
pub const RC_FAST_CLK: Rate = Rate::from_khz(17500);
}
#[doc(hidden)]

View File

@ -39,7 +39,6 @@ use core::marker::PhantomData;
#[instability::unstable]
pub use dma::*;
use enumset::{EnumSet, EnumSetType};
use fugit::{HertzU32, RateExtU32};
#[cfg(place_spi_driver_in_ram)]
use procmacros::ram;
@ -61,6 +60,7 @@ use crate::{
private::{self, Sealed},
spi::AnySpi,
system::PeripheralGuard,
time::Rate,
Async,
Blocking,
Cpu,
@ -426,7 +426,7 @@ pub enum ClockSource {
}
/// SPI peripheral configuration
#[derive(Clone, Copy, Debug, PartialEq, Eq, procmacros::BuilderLite)]
#[derive(Clone, Copy, Debug, PartialEq, Eq, Hash, procmacros::BuilderLite)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
#[non_exhaustive]
pub struct Config {
@ -445,7 +445,7 @@ pub struct Config {
/// The target frequency
#[builder_lite(skip_setter)]
frequency: HertzU32,
frequency: Rate,
/// The clock source
#[cfg_attr(not(feature = "unstable"), builder_lite(skip))]
@ -466,7 +466,7 @@ impl Default for Config {
fn default() -> Self {
let mut this = Config {
reg: Ok(0),
frequency: 1_u32.MHz(),
frequency: Rate::from_mhz(1),
clock_source: ClockSource::Apb,
mode: Mode::_0,
read_bit_order: BitOrder::MsbFirst,
@ -479,20 +479,9 @@ impl Default for Config {
}
}
impl core::hash::Hash for Config {
fn hash<H: core::hash::Hasher>(&self, state: &mut H) {
self.reg.hash(state);
self.frequency.to_Hz().hash(state); // HertzU32 doesn't implement Hash
self.clock_source.hash(state);
self.mode.hash(state);
self.read_bit_order.hash(state);
self.write_bit_order.hash(state);
}
}
impl Config {
/// Set the frequency of the SPI bus clock.
pub fn with_frequency(mut self, frequency: HertzU32) -> Self {
pub fn with_frequency(mut self, frequency: Rate) -> Self {
self.frequency = frequency;
self.reg = self.recalculate();
@ -544,8 +533,8 @@ impl Config {
let mut besterr: i32 = 0;
let mut errval: i32;
let raw_freq = self.frequency.raw() as i32;
let raw_apb_freq = apb_clk_freq.raw() as i32;
let raw_freq = self.frequency.as_hz() as i32;
let raw_apb_freq = apb_clk_freq.as_hz() as i32;
// Start at n = 2. We need to be able to set h/l so we have at least
// one high and one low pulse.
@ -624,8 +613,8 @@ pub enum ConfigError {}
/// # use esp_hal::spi::master::{Config, Spi};
/// let mut spi = Spi::new(
/// peripherals.SPI2,
/// Config::default().with_frequency(100.kHz()).with_mode(Mode::_0)
/// )?
/// Config::default().with_frequency(Rate::from_khz(100)).
/// with_mode(Mode::_0) )?
/// .with_sck(peripherals.GPIO0)
/// .with_mosi(peripherals.GPIO1)
/// .with_miso(peripherals.GPIO2);
@ -769,8 +758,8 @@ impl<'d> Spi<'d, Blocking> {
///
/// let mut spi = Spi::new(
/// peripherals.SPI2,
/// Config::default().with_frequency(100.kHz()).with_mode(Mode::_0)
/// )?
/// Config::default().with_frequency(Rate::from_khz(100)).
/// with_mode(Mode::_0) )?
/// .with_dma(dma_channel)
/// .with_buffers(dma_rx_buf, dma_tx_buf);
/// # Ok(())
@ -1237,8 +1226,8 @@ mod dma {
///
/// let mut spi = Spi::new(
/// peripherals.SPI2,
/// Config::default().with_frequency(100.kHz()).with_mode(Mode::_0)
/// )?
/// Config::default().with_frequency(Rate::from_khz(100)).
/// with_mode(Mode::_0) )?
/// .with_dma(dma_channel)
/// .with_buffers(dma_rx_buf, dma_tx_buf);
/// # Ok(())

View File

@ -1,31 +1,427 @@
//! # Time
//! # Timekeeping
//!
//! The `time` module offers a way to get the system now.
//! This module provides types for representing frequency and duration, as well
//! as an instant in time. Time is measured since boot, and can be accessed
//! by the [`Instant::now`] function.
pub use fugit::{ExtU64, RateExtU32};
use core::fmt::{Debug, Display, Formatter, Result as FmtResult};
#[cfg(esp32)]
use crate::peripherals::TIMG0;
/// Represents a duration of time.
///
/// The resolution is 1 microsecond, represented as a 64-bit unsigned integer.
pub type Duration = fugit::Duration<u64, 1, 1_000_000>;
type InnerRate = fugit::Rate<u32, 1, 1>;
type InnerInstant = fugit::Instant<u64, 1, 1_000_000>;
type InnerDuration = fugit::Duration<u64, 1, 1_000_000>;
/// Represents a rate or frequency of events.
#[derive(Clone, Copy, PartialEq, Eq, PartialOrd, Ord)]
pub struct Rate(InnerRate);
impl core::hash::Hash for Rate {
#[inline]
fn hash<H: core::hash::Hasher>(&self, state: &mut H) {
self.as_hz().hash(state);
}
}
impl Display for Rate {
#[inline]
fn fmt(&self, f: &mut Formatter<'_>) -> FmtResult {
write!(f, "{} Hz", self.as_hz())
}
}
impl Debug for Rate {
#[inline]
fn fmt(&self, f: &mut Formatter<'_>) -> FmtResult {
write!(f, "Rate({} Hz)", self.as_hz())
}
}
#[cfg(feature = "defmt")]
impl defmt::Format for Rate {
#[inline]
fn format(&self, f: defmt::Formatter<'_>) {
defmt::write!(f, "{=u32} Hz", self.as_hz())
}
}
impl Rate {
/// Shorthand for creating a rate which represents hertz.
#[inline]
pub const fn from_hz(val: u32) -> Self {
Self(InnerRate::Hz(val))
}
/// Shorthand for creating a rate which represents kilohertz.
#[inline]
pub const fn from_khz(val: u32) -> Self {
Self(InnerRate::kHz(val))
}
/// Shorthand for creating a rate which represents megahertz.
#[inline]
pub const fn from_mhz(val: u32) -> Self {
Self(InnerRate::MHz(val))
}
/// Convert the `Rate` to an interger number of Hz.
#[inline]
pub const fn as_hz(&self) -> u32 {
self.0.to_Hz()
}
/// Convert the `Rate` to an interger number of kHz.
#[inline]
pub const fn as_khz(&self) -> u32 {
self.0.to_kHz()
}
/// Convert the `Rate` to an interger number of MHz.
#[inline]
pub const fn as_mhz(&self) -> u32 {
self.0.to_MHz()
}
/// Convert the `Rate` to a `Duration`.
#[inline]
pub const fn as_duration(&self) -> Duration {
Duration::from_micros(1_000_000 / self.as_hz() as u64)
}
}
impl core::ops::Div for Rate {
type Output = u32;
#[inline]
fn div(self, rhs: Self) -> Self::Output {
self.0 / rhs.0
}
}
impl core::ops::Mul<u32> for Rate {
type Output = Rate;
#[inline]
fn mul(self, rhs: u32) -> Self::Output {
Rate(self.0 * rhs)
}
}
impl core::ops::Div<u32> for Rate {
type Output = Rate;
#[inline]
fn div(self, rhs: u32) -> Self::Output {
Rate(self.0 / rhs)
}
}
/// Represents an instant in time.
///
/// The resolution is 1 microsecond, represented as a 64-bit unsigned integer.
pub type Instant = fugit::Instant<u64, 1, 1_000_000>;
#[derive(Clone, Copy, PartialEq, Eq, PartialOrd, Ord)]
pub struct Instant(InnerInstant);
/// Provides time since system start in microseconds precision.
///
/// The counter wont measure time in sleep-mode.
///
/// The timer will wrap after
#[cfg_attr(esp32, doc = "36_558 years")]
#[cfg_attr(esp32s2, doc = "7_311 years")]
#[cfg_attr(not(any(esp32, esp32s2)), doc = "more than 7 years")]
pub fn now() -> Instant {
impl Debug for Instant {
#[inline]
fn fmt(&self, f: &mut Formatter<'_>) -> FmtResult {
write!(
f,
"Instant({} µs since epoch)",
self.duration_since_epoch().as_micros()
)
}
}
impl Display for Instant {
#[inline]
fn fmt(&self, f: &mut Formatter<'_>) -> FmtResult {
write!(
f,
"{} µs since epoch",
self.duration_since_epoch().as_micros()
)
}
}
#[cfg(feature = "defmt")]
impl defmt::Format for Instant {
#[inline]
fn format(&self, f: defmt::Formatter<'_>) {
defmt::write!(
f,
"{=u64} µs since epoch",
self.duration_since_epoch().as_micros()
)
}
}
impl Instant {
/// Represents the moment the system booted.
pub const EPOCH: Instant = Instant(InnerInstant::from_ticks(0));
/// Returns the current instant.
///
/// The counter wont measure time in sleep-mode.
///
/// The timer has a 1 microsecond resolution and will wrap after
#[cfg_attr(esp32, doc = "36_558 years")]
#[cfg_attr(esp32s2, doc = "7_311 years")]
#[cfg_attr(not(any(esp32, esp32s2)), doc = "more than 7 years")]
#[inline]
pub fn now() -> Self {
now()
}
#[inline]
pub(crate) fn from_ticks(ticks: u64) -> Self {
Instant(InnerInstant::from_ticks(ticks))
}
/// Returns the elapsed `Duration` since boot.
#[inline]
pub fn duration_since_epoch(&self) -> Duration {
Self::EPOCH.elapsed()
}
/// Returns the elapsed `Duration` since this `Instant` was created.
#[inline]
pub fn elapsed(&self) -> Duration {
Self::now() - *self
}
}
impl core::ops::Add<Duration> for Instant {
type Output = Self;
#[inline]
fn add(self, rhs: Duration) -> Self::Output {
Instant(self.0 + rhs.0)
}
}
impl core::ops::AddAssign<Duration> for Instant {
#[inline]
fn add_assign(&mut self, rhs: Duration) {
self.0 += rhs.0;
}
}
impl core::ops::Sub for Instant {
type Output = Duration;
#[inline]
fn sub(self, rhs: Self) -> Self::Output {
Duration(self.0 - rhs.0)
}
}
impl core::ops::Sub<Duration> for Instant {
type Output = Self;
#[inline]
fn sub(self, rhs: Duration) -> Self::Output {
Instant(self.0 - rhs.0)
}
}
impl core::ops::SubAssign<Duration> for Instant {
#[inline]
fn sub_assign(&mut self, rhs: Duration) {
self.0 -= rhs.0;
}
}
/// Represents a duration of time.
#[derive(Clone, Copy, PartialEq, Eq, PartialOrd, Ord)]
pub struct Duration(InnerDuration);
impl Debug for Duration {
#[inline]
fn fmt(&self, f: &mut Formatter<'_>) -> FmtResult {
write!(f, "Duration({} µs)", self.as_micros())
}
}
impl Display for Duration {
#[inline]
fn fmt(&self, f: &mut Formatter<'_>) -> FmtResult {
write!(f, "{} µs", self.as_micros())
}
}
#[cfg(feature = "defmt")]
impl defmt::Format for Duration {
#[inline]
fn format(&self, f: defmt::Formatter<'_>) {
defmt::write!(f, "{=u64} µs", self.as_micros())
}
}
impl Duration {
/// A duration of zero time.
pub const ZERO: Self = Self(InnerDuration::from_ticks(0));
/// A duration representing the maximum possible time.
pub const MAX: Self = Self(InnerDuration::from_ticks(u64::MAX));
/// Creates a duration which represents microseconds.
#[inline]
pub const fn from_micros(val: u64) -> Self {
Self(InnerDuration::micros(val))
}
/// Creates a duration which represents milliseconds.
#[inline]
pub const fn from_millis(val: u64) -> Self {
Self(InnerDuration::millis(val))
}
/// Creates a duration which represents seconds.
#[inline]
pub const fn from_secs(val: u64) -> Self {
Self(InnerDuration::secs(val))
}
/// Creates a duration which represents minutes.
#[inline]
pub const fn from_minutes(val: u64) -> Self {
Self(InnerDuration::minutes(val))
}
/// Creates a duration which represents hours.
#[inline]
pub const fn from_hours(val: u64) -> Self {
Self(InnerDuration::hours(val))
}
delegate::delegate! {
#[inline]
to self.0 {
/// Convert the `Duration` to an interger number of microseconds.
#[call(to_micros)]
pub const fn as_micros(&self) -> u64;
/// Convert the `Duration` to an interger number of milliseconds.
#[call(to_millis)]
pub const fn as_millis(&self) -> u64;
/// Convert the `Duration` to an interger number of seconds.
#[call(to_secs)]
pub const fn as_secs(&self) -> u64;
/// Convert the `Duration` to an interger number of minutes.
#[call(to_minutes)]
pub const fn as_minutes(&self) -> u64;
/// Convert the `Duration` to an interger number of hours.
#[call(to_hours)]
pub const fn as_hours(&self) -> u64;
}
}
/// Add two durations while checking for overflow.
#[inline]
pub const fn checked_add(self, rhs: Self) -> Option<Self> {
if let Some(val) = self.0.checked_add(rhs.0) {
Some(Duration(val))
} else {
None
}
}
/// Subtract two durations while checking for overflow.
#[inline]
pub const fn checked_sub(self, rhs: Self) -> Option<Self> {
if let Some(val) = self.0.checked_sub(rhs.0) {
Some(Duration(val))
} else {
None
}
}
/// Add two durations, returning the maximum value if overflow occurred.
#[inline]
pub const fn saturating_add(self, rhs: Self) -> Self {
if let Some(val) = self.checked_add(rhs) {
val
} else {
Self::MAX
}
}
/// Subtract two durations, returning the minimum value if the result would
/// be negative.
#[inline]
pub const fn saturating_sub(self, rhs: Self) -> Self {
if let Some(val) = self.checked_sub(rhs) {
val
} else {
Self::ZERO
}
}
}
impl core::ops::Add for Duration {
type Output = Self;
#[inline]
fn add(self, rhs: Self) -> Self::Output {
Duration(self.0 + rhs.0)
}
}
impl core::ops::AddAssign for Duration {
#[inline]
fn add_assign(&mut self, rhs: Self) {
self.0 += rhs.0;
}
}
impl core::ops::Sub for Duration {
type Output = Self;
#[inline]
fn sub(self, rhs: Self) -> Self::Output {
Duration(self.0 - rhs.0)
}
}
impl core::ops::SubAssign for Duration {
#[inline]
fn sub_assign(&mut self, rhs: Self) {
self.0 -= rhs.0;
}
}
impl core::ops::Mul<u32> for Duration {
type Output = Self;
#[inline]
fn mul(self, rhs: u32) -> Self::Output {
Duration(self.0 * rhs)
}
}
impl core::ops::Div<u32> for Duration {
type Output = Self;
#[inline]
fn div(self, rhs: u32) -> Self::Output {
Duration(self.0 / rhs)
}
}
impl core::ops::Div<Duration> for Duration {
type Output = u64;
#[inline]
fn div(self, rhs: Duration) -> Self::Output {
self.0 / rhs.0
}
}
#[inline]
fn now() -> Instant {
#[cfg(esp32)]
let (ticks, div) = {
// on ESP32 use LACT
@ -63,7 +459,7 @@ pub fn now() -> Instant {
#[cfg(esp32)]
pub(crate) fn time_init() {
let apb = crate::Clocks::get().apb_clock.to_Hz();
let apb = crate::Clocks::get().apb_clock.as_hz();
// we assume 80MHz APB clock source - there is no way to configure it in a
// different way currently
assert_eq!(apb, 80_000_000u32);

View File

@ -34,7 +34,7 @@
//! let timg0 = TimerGroup::new(peripherals.TIMG0);
//! let mut periodic = PeriodicTimer::new(timg0.timer0);
//!
//! periodic.start(1.secs());
//! periodic.start(Duration::from_secs(1));
//! loop {
//! periodic.wait();
//! }
@ -43,12 +43,11 @@
use core::marker::PhantomData;
use fugit::{ExtU64, Instant, MicrosDurationU64};
use crate::{
interrupt::{InterruptConfigurable, InterruptHandler},
peripheral::{Peripheral, PeripheralRef},
peripherals::Interrupt,
time::{Duration, Instant},
Async,
Blocking,
Cpu,
@ -94,11 +93,11 @@ pub trait Timer: Into<AnyTimer> + 'static + crate::private::Sealed {
/// The current timer value.
#[doc(hidden)]
fn now(&self) -> Instant<u64, 1, 1_000_000>;
fn now(&self) -> Instant;
/// Load a target value into the timer.
#[doc(hidden)]
fn load_value(&self, value: MicrosDurationU64) -> Result<(), Error>;
fn load_value(&self, value: Duration) -> Result<(), Error>;
/// Enable auto reload of the loaded value.
#[doc(hidden)]
@ -174,21 +173,21 @@ impl OneShotTimer<'_, Async> {
/// Delay for *at least* `ns` nanoseconds.
pub async fn delay_nanos_async(&mut self, ns: u32) {
self.delay_async(MicrosDurationU64::from_ticks(ns.div_ceil(1000) as u64))
self.delay_async(Duration::from_micros(ns.div_ceil(1000) as u64))
.await
}
/// Delay for *at least* `ms` milliseconds.
pub async fn delay_millis_async(&mut self, ms: u32) {
self.delay_async((ms as u64).millis()).await;
self.delay_async(Duration::from_millis(ms as u64)).await;
}
/// Delay for *at least* `us` microseconds.
pub async fn delay_micros_async(&mut self, us: u32) {
self.delay_async((us as u64).micros()).await;
self.delay_async(Duration::from_micros(us as u64)).await;
}
async fn delay_async(&mut self, us: MicrosDurationU64) {
async fn delay_async(&mut self, us: Duration) {
unwrap!(self.schedule(us));
self.inner.wait().await;
self.stop();
@ -202,20 +201,20 @@ where
{
/// Delay for *at least* `ms` milliseconds.
pub fn delay_millis(&mut self, ms: u32) {
self.delay((ms as u64).millis());
self.delay(Duration::from_millis(ms as u64));
}
/// Delay for *at least* `us` microseconds.
pub fn delay_micros(&mut self, us: u32) {
self.delay((us as u64).micros());
self.delay(Duration::from_micros(us as u64));
}
/// Delay for *at least* `ns` nanoseconds.
pub fn delay_nanos(&mut self, ns: u32) {
self.delay((ns.div_ceil(1000) as u64).micros())
self.delay(Duration::from_micros(ns.div_ceil(1000) as u64))
}
fn delay(&mut self, us: MicrosDurationU64) {
fn delay(&mut self, us: Duration) {
self.schedule(us).unwrap();
while !self.inner.is_interrupt_set() {
@ -227,7 +226,7 @@ where
}
/// Start counting until the given timeout and raise an interrupt
pub fn schedule(&mut self, timeout: MicrosDurationU64) -> Result<(), Error> {
pub fn schedule(&mut self, timeout: Duration) -> Result<(), Error> {
if self.inner.is_running() {
self.inner.stop();
}
@ -311,7 +310,7 @@ where
Dm: DriverMode,
{
/// Start a new count down.
pub fn start(&mut self, timeout: MicrosDurationU64) -> Result<(), Error> {
pub fn start(&mut self, period: Duration) -> Result<(), Error> {
if self.inner.is_running() {
self.inner.stop();
}
@ -320,7 +319,7 @@ where
self.inner.reset();
self.inner.enable_auto_reload(true);
self.inner.load_value(timeout)?;
self.inner.load_value(period)?;
self.inner.start();
Ok(())
@ -393,8 +392,8 @@ impl Timer for AnyTimer {
fn stop(&self);
fn reset(&self);
fn is_running(&self) -> bool;
fn now(&self) -> Instant<u64, 1, 1_000_000>;
fn load_value(&self, value: MicrosDurationU64) -> Result<(), Error>;
fn now(&self) -> Instant;
fn load_value(&self, value: Duration) -> Result<(), Error>;
fn enable_auto_reload(&self, auto_reload: bool);
fn enable_interrupt(&self, state: bool);
fn clear_interrupt(&self);

View File

@ -19,8 +19,6 @@
use core::fmt::Debug;
use fugit::{Instant, MicrosDurationU64};
use super::{Error, Timer as _};
use crate::{
interrupt::{self, InterruptHandler},
@ -28,6 +26,7 @@ use crate::{
peripherals::{Interrupt, SYSTIMER},
sync::{lock, RawMutex},
system::{Peripheral as PeripheralEnable, PeripheralClockControl},
time::{Duration, Instant},
Cpu,
};
@ -72,29 +71,33 @@ impl SystemTimer {
}
/// Returns the tick frequency of the underlying timer unit.
#[inline]
pub fn ticks_per_second() -> u64 {
cfg_if::cfg_if! {
if #[cfg(esp32s2)] {
const MULTIPLIER: u64 = 2_000_000;
const MULTIPLIER: u32 = 2;
const DIVIDER: u32 = 1;
} else if #[cfg(esp32h2)] {
// The counters and comparators are driven using `XTAL_CLK`.
// The average clock frequency is fXTAL_CLK/2, which is 16 MHz.
// The timer counting is incremented by 1/16 μs on each `CNT_CLK` cycle.
const MULTIPLIER: u64 = 10_000_000 / 20;
const MULTIPLIER: u32 = 1;
const DIVIDER: u32 = 2;
} else {
// The counters and comparators are driven using `XTAL_CLK`.
// The average clock frequency is fXTAL_CLK/2.5, which is 16 MHz.
// The timer counting is incremented by 1/16 μs on each `CNT_CLK` cycle.
const MULTIPLIER: u64 = 10_000_000 / 25;
const MULTIPLIER: u32 = 4;
const DIVIDER: u32 = 10;
}
}
let xtal_freq_mhz = crate::clock::Clocks::xtal_freq().to_MHz();
xtal_freq_mhz as u64 * MULTIPLIER
let xtal_freq_mhz = crate::clock::Clocks::xtal_freq().as_hz();
((xtal_freq_mhz * MULTIPLIER) / DIVIDER) as u64
}
/// Create a new instance.
pub fn new(_systimer: SYSTIMER) -> Self {
// Don't reset Systimer as it will break `time::now`, only enable it
// Don't reset Systimer as it will break `time::Instant::now`, only enable it
PeripheralClockControl::enable(PeripheralEnable::Systimer);
#[cfg(soc_etm)]
@ -125,7 +128,7 @@ impl SystemTimer {
///
/// - Disabling a `Unit` whilst [`Alarm`]s are using it will affect the
/// [`Alarm`]s operation.
/// - Disabling Unit0 will affect [`now`](crate::time::now).
/// - Disabling Unit0 will affect [`Instant::now`].
pub unsafe fn configure_unit(unit: Unit, config: UnitConfig) {
unit.configure(config)
}
@ -140,8 +143,7 @@ impl SystemTimer {
///
/// - Modifying a unit's count whilst [`Alarm`]s are using it may cause
/// unexpected behaviour
/// - Any modification of the unit0 count will affect
/// [`now`](crate::time::now).
/// - Any modification of the unit0 count will affect [`Instant::now`]
pub unsafe fn set_unit_value(unit: Unit, value: u64) {
unit.set_count(value)
}
@ -475,7 +477,7 @@ impl super::Timer for Alarm {
self.is_enabled()
}
fn now(&self) -> Instant<u64, 1, 1_000_000> {
fn now(&self) -> Instant {
// This should be safe to access from multiple contexts; worst case
// scenario the second accessor ends up reading an older time stamp.
@ -483,13 +485,13 @@ impl super::Timer for Alarm {
let us = ticks / (SystemTimer::ticks_per_second() / 1_000_000);
Instant::<u64, 1, 1_000_000>::from_ticks(us)
Instant::from_ticks(us)
}
fn load_value(&self, value: MicrosDurationU64) -> Result<(), Error> {
fn load_value(&self, value: Duration) -> Result<(), Error> {
let mode = self.mode();
let us = value.ticks();
let us = value.as_micros();
let ticks = us * (SystemTimer::ticks_per_second() / 1_000_000);
if matches!(mode, ComparatorMode::Period) {
@ -713,7 +715,6 @@ pub mod etm {
//! # Level,
//! # Pull,
//! # };
//! # use fugit::ExtU32;
//! let syst = SystemTimer::new(peripherals.SYSTIMER);
//! let etm = Etm::new(peripherals.SOC_ETM);
//! let gpio_ext = Channels::new(peripherals.GPIO_SD);

View File

@ -36,7 +36,7 @@
//! let now = timer0.now();
//!
//! // Wait for timeout:
//! timer0.load_value(1.secs());
//! timer0.load_value(Duration::from_secs(1));
//! timer0.start();
//!
//! while !timer0.is_interrupt_set() {
@ -58,7 +58,7 @@
//! let timg0 = TimerGroup::new(peripherals.TIMG0);
//! let mut wdt = timg0.wdt;
//!
//! wdt.set_timeout(MwdtStage::Stage0, 5_000.millis());
//! wdt.set_timeout(MwdtStage::Stage0, Duration::from_millis(5_000));
//! wdt.enable();
//!
//! loop {
@ -68,8 +68,6 @@
//! ```
use core::marker::PhantomData;
use fugit::{HertzU32, Instant, MicrosDurationU64};
use super::Error;
#[cfg(any(esp32c6, esp32h2))]
use crate::soc::constants::TIMG_DEFAULT_CLK_SRC;
@ -82,6 +80,7 @@ use crate::{
private::Sealed,
sync::{lock, RawMutex},
system::PeripheralClockControl,
time::{Duration, Instant, Rate},
};
const NUM_TIMG: usize = 1 + cfg!(timg1) as usize;
@ -152,7 +151,7 @@ impl TimerGroupInstance for TIMG0 {
fn reset_peripheral() {
// FIXME: for TIMG0 do nothing for now because the reset breaks
// `time::now`
// `time::Instant::now`
}
fn configure_wdt_src_clk() {
@ -288,11 +287,11 @@ impl super::Timer for Timer {
self.is_counter_active()
}
fn now(&self) -> Instant<u64, 1, 1_000_000> {
fn now(&self) -> Instant {
self.now()
}
fn load_value(&self, value: MicrosDurationU64) -> Result<(), Error> {
fn load_value(&self, value: Duration) -> Result<(), Error> {
self.load_value(value)
}
@ -449,7 +448,7 @@ impl Timer {
self.t().config().modify(|_, w| w.alarm_en().bit(state));
}
fn load_value(&self, value: MicrosDurationU64) -> Result<(), Error> {
fn load_value(&self, value: Duration) -> Result<(), Error> {
cfg_if::cfg_if! {
if #[cfg(esp32h2)] {
// ESP32-H2 is using PLL_48M_CLK source instead of APB_CLK
@ -485,7 +484,7 @@ impl Timer {
self.set_alarm_active(periodic);
}
fn now(&self) -> Instant<u64, 1, 1_000_000> {
fn now(&self) -> Instant {
let t = self.t();
t.update().write(|w| w.update().set_bit());
@ -507,7 +506,7 @@ impl Timer {
}
let micros = ticks_to_timeout(ticks, clk_src, self.divider());
Instant::<u64, 1, 1_000_000>::from_ticks(micros)
Instant::from_ticks(micros)
}
fn divider(&self) -> u32 {
@ -535,32 +534,20 @@ impl Timer {
}
}
fn ticks_to_timeout<F>(ticks: u64, clock: F, divider: u32) -> u64
where
F: Into<HertzU32>,
{
let clock: HertzU32 = clock.into();
fn ticks_to_timeout(ticks: u64, clock: Rate, divider: u32) -> u64 {
// 1_000_000 is used to get rid of `float` calculations
let period: u64 = 1_000_000 * 1_000_000 / (clock.to_Hz() as u64 / divider as u64);
let period: u64 = 1_000_000 * 1_000_000 / (clock.as_hz() as u64 / divider as u64);
ticks * period / 1_000_000
}
fn timeout_to_ticks<T, F>(timeout: T, clock: F, divider: u32) -> u64
where
T: Into<MicrosDurationU64>,
F: Into<HertzU32>,
{
let timeout: MicrosDurationU64 = timeout.into();
let micros = timeout.to_micros();
let clock: HertzU32 = clock.into();
fn timeout_to_ticks(timeout: Duration, clock: Rate, divider: u32) -> u64 {
let micros = timeout.as_micros();
// 1_000_000 is used to get rid of `float` calculations
let period: u64 = 1_000_000 * 1_000_000 / (clock.to_Hz() as u64 / divider as u64);
let period: u64 = 1_000_000 * 1_000_000 / ((clock.as_hz() / divider) as u64);
(1_000_000 * micros / period as u64) as u64
(1_000_000 * micros) / period
}
/// Behavior of the MWDT stage if it times out.
@ -696,8 +683,8 @@ where
}
/// Set the timeout, in microseconds, of the watchdog timer
pub fn set_timeout(&mut self, stage: MwdtStage, timeout: MicrosDurationU64) {
let timeout_raw = (timeout.to_nanos() * 10 / 125) as u32;
pub fn set_timeout(&mut self, stage: MwdtStage, timeout: Duration) {
let timeout_raw = (timeout.as_micros() * 10_000 / 125) as u32;
let reg_block = unsafe { &*TG::register_block() };

View File

@ -765,7 +765,7 @@ where
#[cfg(not(any(esp32h2, esp32c6)))]
{
let apb_clock = crate::clock::Clocks::get().apb_clock;
assert!(apb_clock == fugit::HertzU32::MHz(80));
assert!(apb_clock.as_mhz() == 80);
}
// Unpack the baud rate timings and convert them to the values needed for the

View File

@ -63,7 +63,7 @@
//!
//! loop {
//! println!("Send `#` character or >=30 characters");
//! delay.delay(1.secs());
//! delay.delay(Duration::from_secs(1));
//! }
//! # }
//!
@ -2371,9 +2371,9 @@ impl Info {
let clocks = Clocks::get();
let clk = match config.clock_source {
ClockSource::Apb => clocks.apb_clock.to_Hz(),
ClockSource::Xtal => clocks.xtal_clock.to_Hz(),
ClockSource::RcFast => crate::soc::constants::RC_FAST_CLK.to_Hz(),
ClockSource::Apb => clocks.apb_clock.as_hz(),
ClockSource::Xtal => clocks.xtal_clock.as_hz(),
ClockSource::RcFast => crate::soc::constants::RC_FAST_CLK.as_hz(),
};
if config.clock_source == ClockSource::RcFast {
@ -2419,9 +2419,9 @@ impl Info {
fn change_baud(&self, config: &Config) {
let clocks = Clocks::get();
let clk = match config.clock_source {
ClockSource::Apb => clocks.apb_clock.to_Hz(),
ClockSource::Xtal => clocks.xtal_clock.to_Hz(),
ClockSource::RcFast => crate::soc::constants::RC_FAST_CLK.to_Hz(),
ClockSource::Apb => clocks.apb_clock.as_hz(),
ClockSource::Xtal => clocks.xtal_clock.as_hz(),
ClockSource::RcFast => crate::soc::constants::RC_FAST_CLK.as_hz(),
};
let max_div = 0b1111_1111_1111 - 1;
@ -2476,9 +2476,9 @@ impl Info {
#[cfg(any(esp32, esp32s2))]
fn change_baud(&self, config: &Config) {
let clk = match config.clock_source {
ClockSource::Apb => Clocks::get().apb_clock.to_Hz(),
ClockSource::Apb => Clocks::get().apb_clock.as_hz(),
// ESP32(/-S2) TRM, section 3.2.4.2 (6.2.4.2 for S2)
ClockSource::RefTick => crate::soc::constants::REF_TICK.to_Hz(),
ClockSource::RefTick => crate::soc::constants::REF_TICK.as_hz(),
};
self.regs().conf0().modify(|_, w| {

View File

@ -88,7 +88,7 @@
//!
//! loop {
//! println!("Send keystrokes to see the interrupt trigger");
//! delay.delay(1.secs());
//! delay.delay(Duration::from_secs(1));
//! }
//! # }
//!

View File

@ -24,7 +24,6 @@ critical-section = "1.2.0"
enumset = { version = "1.1.5", default-features = false, optional = true }
embedded-io = { version = "0.6.1", default-features = false }
embedded-io-async = { version = "0.6.1" }
fugit = "0.3.7"
heapless = { version = "0.8.0", default-features = false, features = [
"portable-atomic",
] }

View File

@ -661,7 +661,9 @@ unsafe extern "C" fn ble_npl_time_ms_to_ticks(
unsafe extern "C" fn ble_npl_time_get() -> u32 {
trace!("ble_npl_time_get");
esp_hal::time::now().duration_since_epoch().to_millis() as u32
esp_hal::time::Instant::now()
.duration_since_epoch()
.as_millis() as u32
}
unsafe extern "C" fn ble_npl_callout_set_arg(

View File

@ -108,11 +108,11 @@ use esp_hal as hal;
use esp_hal::peripheral::Peripheral;
#[cfg(not(feature = "esp32"))]
use esp_hal::timer::systimer::Alarm;
use fugit::MegahertzU32;
use hal::{
clock::Clocks,
rng::{Rng, Trng},
system::RadioClockController,
time::Rate,
timer::{timg::Timer as TimgTimer, AnyTimer, PeriodicTimer},
Blocking,
};
@ -370,9 +370,9 @@ pub fn init<'d, T: EspWifiTimerSource, R: EspWifiRngSource>(
_radio_clocks: impl Peripheral<P = hal::peripherals::RADIO_CLK> + 'd,
) -> Result<EspWifiController<'d>, InitializationError> {
// A minimum clock of 80MHz is required to operate WiFi module.
const MIN_CLOCK: u32 = 80;
const MIN_CLOCK: Rate = Rate::from_mhz(80);
let clocks = Clocks::get();
if clocks.cpu_clock < MegahertzU32::MHz(MIN_CLOCK) {
if clocks.cpu_clock < MIN_CLOCK {
return Err(InitializationError::WrongClockConfig);
}

View File

@ -9,14 +9,14 @@ use crate::{
interrupt::{self, TrapFrame},
peripherals::{self, Interrupt},
riscv,
time::Rate,
},
preempt::task_switch,
TimeBase,
};
/// The timer responsible for time slicing.
const TIMESLICE_FREQUENCY: fugit::HertzU64 =
fugit::HertzU64::from_raw(crate::CONFIG.tick_rate_hz as u64);
const TIMESLICE_FREQUENCY: Rate = Rate::from_hz(crate::CONFIG.tick_rate_hz);
// Time keeping
pub const TICKS_PER_SECOND: u64 = 1_000_000;
@ -29,7 +29,7 @@ pub(crate) fn setup_timer(mut alarm0: TimeBase) {
let cb: extern "C" fn() = unsafe { core::mem::transmute(handler as *const ()) };
alarm0.set_interrupt_handler(InterruptHandler::new(cb, interrupt::Priority::Priority1));
unwrap!(alarm0.start(TIMESLICE_FREQUENCY.into_duration()));
unwrap!(alarm0.start(TIMESLICE_FREQUENCY.as_duration()));
TIMER.with(|timer| {
alarm0.enable_interrupt(true);
timer.replace(alarm0);
@ -92,7 +92,9 @@ pub(crate) fn yield_task() {
/// Current systimer count value
/// A tick is 1 / 1_000_000 seconds
pub(crate) fn systimer_count() -> u64 {
esp_hal::time::now().ticks()
esp_hal::time::Instant::now()
.duration_since_epoch()
.as_micros()
}
// TODO: use an Instance type instead...

View File

@ -1,14 +1,13 @@
use esp_hal::interrupt::InterruptHandler;
use crate::{
hal::{interrupt, trapframe::TrapFrame, xtensa_lx, xtensa_lx_rt},
hal::{interrupt, time::Rate, trapframe::TrapFrame, xtensa_lx, xtensa_lx_rt},
preempt::task_switch,
TimeBase,
};
/// The timer responsible for time slicing.
const TIMESLICE_FREQUENCY: fugit::HertzU64 =
fugit::HertzU64::from_raw(crate::CONFIG.tick_rate_hz as u64);
const TIMESLICE_FREQUENCY: Rate = Rate::from_hz(crate::CONFIG.tick_rate_hz);
use super::TIMER;
@ -18,7 +17,9 @@ pub const TICKS_PER_SECOND: u64 = 1_000_000;
/// This function must not be called in a critical section. Doing so may return
/// an incorrect value.
pub(crate) fn systimer_count() -> u64 {
esp_hal::time::now().ticks()
esp_hal::time::Instant::now()
.duration_since_epoch()
.as_micros()
}
pub(crate) fn setup_timer(mut timer1: TimeBase) {
@ -26,7 +27,7 @@ pub(crate) fn setup_timer(mut timer1: TimeBase) {
unsafe { core::mem::transmute::<*const (), extern "C" fn()>(handler as *const ()) },
interrupt::Priority::Priority2,
));
unwrap!(timer1.start(TIMESLICE_FREQUENCY.into_duration()));
unwrap!(timer1.start(TIMESLICE_FREQUENCY.as_duration()));
TIMER.with(|timer| {
timer1.enable_interrupt(true);
timer.replace(timer1);

View File

@ -1500,7 +1500,9 @@ pub unsafe extern "C" fn log_writev(
///
/// *************************************************************************
pub unsafe extern "C" fn log_timestamp() -> u32 {
esp_hal::time::now().duration_since_epoch().to_millis() as u32
esp_hal::time::Instant::now()
.duration_since_epoch()
.as_millis() as u32
}
/// **************************************************************************

View File

@ -8,11 +8,13 @@ use smoltcp::{
use super::{WifiApDevice, WifiController, WifiDevice, WifiDeviceMode, WifiError, WifiStaDevice};
use crate::EspWifiController;
// [esp_hal::time::now()] as a smoltcp [`Instant`]
/// [esp_hal::time::Instant] as a smoltcp [`Instant`]
#[cfg(feature = "smoltcp")]
fn timestamp() -> smoltcp::time::Instant {
smoltcp::time::Instant::from_micros(
esp_hal::time::now().duration_since_epoch().to_micros() as i64
esp_hal::time::Instant::now()
.duration_since_epoch()
.as_micros() as i64,
)
}

View File

@ -31,7 +31,6 @@ esp-ieee802154 = { path = "../esp-ieee802154", optional = true }
esp-println = { path = "../esp-println", features = ["log"] }
esp-storage = { path = "../esp-storage", optional = true }
esp-wifi = { path = "../esp-wifi", features = ["log"], optional = true }
fugit = "0.3.7"
heapless = "0.8.0"
hmac = { version = "0.12.1", default-features = false }
ieee80211 = { version = "0.4.0", default-features = false }

View File

@ -11,7 +11,7 @@
use aligned::{Aligned, A64};
use esp_alloc as _;
use esp_backtrace as _;
use esp_hal::{delay::Delay, dma::Mem2Mem, dma_descriptors_chunk_size, main, time::ExtU64};
use esp_hal::{delay::Delay, dma::Mem2Mem, dma_descriptors_chunk_size, main, time::Duration};
use log::{error, info};
extern crate alloc;
@ -140,6 +140,6 @@ fn main() -> ! {
}
loop {
delay.delay(2.secs());
delay.delay(Duration::from_secs(2));
}
}

View File

@ -7,7 +7,7 @@
#![no_main]
use esp_backtrace as _;
use esp_hal::{delay::Delay, dma::Mem2Mem, dma_buffers, main, time::ExtU64};
use esp_hal::{delay::Delay, dma::Mem2Mem, dma_buffers, main, time::Duration};
use log::{error, info};
const DATA_SIZE: usize = 1024 * 10;
@ -71,6 +71,6 @@ fn main() -> ! {
}
loop {
delay.delay(2.secs());
delay.delay(Duration::from_secs(2));
}
}

View File

@ -15,7 +15,7 @@ use esp_backtrace as _;
use esp_hal::{
gpio::{Level, Output, OutputConfig},
rmt::{PulseCode, Rmt, RxChannelAsync, RxChannelConfig, RxChannelCreatorAsync},
time::RateExtU32,
time::Rate,
timer::timg::TimerGroup,
};
use esp_println::{print, println};
@ -46,9 +46,9 @@ async fn main(spawner: Spawner) {
cfg_if::cfg_if! {
if #[cfg(feature = "esp32h2")] {
let freq = 32.MHz();
let freq = Rate::from_mhz(32);
} else {
let freq = 80.MHz();
let freq = Rate::from_mhz(80);
}
};

View File

@ -17,7 +17,7 @@ use esp_backtrace as _;
use esp_hal::{
gpio::Level,
rmt::{PulseCode, Rmt, TxChannelAsync, TxChannelConfig, TxChannelCreatorAsync},
time::RateExtU32,
time::Rate,
timer::timg::TimerGroup,
};
use esp_println::println;
@ -32,9 +32,9 @@ async fn main(_spawner: Spawner) {
cfg_if::cfg_if! {
if #[cfg(feature = "esp32h2")] {
let freq = 32.MHz();
let freq = Rate::from_mhz(32);
} else {
let freq = 80.MHz();
let freq = Rate::from_mhz(80);
}
};

View File

@ -28,7 +28,7 @@ use esp_hal::{
master::{Config, Spi},
Mode,
},
time::RateExtU32,
time::Rate,
timer::timg::TimerGroup,
};
@ -60,7 +60,7 @@ async fn main(_spawner: Spawner) {
let mut spi = Spi::new(
peripherals.SPI2,
Config::default()
.with_frequency(100.kHz())
.with_frequency(Rate::from_khz(100))
.with_mode(Mode::_0),
)
.unwrap()

View File

@ -20,7 +20,7 @@ use esp_hal::{
Pull,
},
main,
time::ExtU64,
time::Duration,
timer::{
systimer::{etm::Event, SystemTimer},
PeriodicTimer,
@ -58,7 +58,7 @@ fn main() -> ! {
let _configured_channel = channel0.setup(&timer_event, &led_task);
let mut timer = PeriodicTimer::new(alarm);
timer.start(1u64.secs()).unwrap();
timer.start(Duration::from_secs(1)).unwrap();
// the LED is controlled by the button without involving the CPU
loop {}

View File

@ -94,19 +94,19 @@ fn main() -> ! {
let mut remaining = nsrc;
hw_hmac.init();
block!(hw_hmac.configure(HmacPurpose::ToUser, KeyId::Key0)).expect("Key purpose mismatch");
let pre_hw_hmac = esp_hal::time::now();
let pre_hw_hmac = esp_hal::time::Instant::now();
while remaining.len() > 0 {
remaining = block!(hw_hmac.update(remaining)).unwrap();
}
block!(hw_hmac.finalize(output.as_mut_slice())).unwrap();
let post_hw_hmac = esp_hal::time::now();
let hw_time = post_hw_hmac - pre_hw_hmac;
let hw_time = pre_hw_hmac.elapsed();
let mut sw_hmac = HmacSha256::new_from_slice(key).expect("HMAC can take key of any size");
let pre_sw_hash = esp_hal::time::now();
let pre_sw_hash = esp_hal::time::Instant::now();
sw_hmac.update(nsrc);
let soft_result = sw_hmac.finalize().into_bytes();
let post_sw_hash = esp_hal::time::now();
let soft_time = post_sw_hash - pre_sw_hash;
let soft_time = pre_sw_hash.elapsed();
for (a, b) in output.iter().zip(soft_result) {
assert_eq!(*a, b);
}

View File

@ -25,7 +25,7 @@ use esp_hal::{
master::{Config, Spi},
Mode,
},
time::RateExtU32,
time::Rate,
};
use esp_println::println;
@ -42,7 +42,7 @@ fn main() -> ! {
let mut spi = Spi::new(
peripherals.SPI2,
Config::default()
.with_frequency(100.kHz())
.with_frequency(Rate::from_khz(100))
.with_mode(Mode::_0),
)
.unwrap()

View File

@ -31,7 +31,7 @@ use esp_hal::{
master::{Config, Spi},
Mode,
},
time::RateExtU32,
time::Rate,
};
extern crate alloc;
use log::*;
@ -91,7 +91,7 @@ fn main() -> ! {
let mut spi = Spi::new(
peripherals.SPI2,
Config::default()
.with_frequency(100.kHz())
.with_frequency(Rate::from_khz(100))
.with_mode(Mode::_0),
)
.unwrap()

View File

@ -18,7 +18,7 @@ use esp_hal::{
delay::Delay,
main,
rng::Rng,
time::ExtU64,
time::Duration,
timer::timg::TimerGroup,
};
use esp_wifi::{init, wifi};
@ -114,6 +114,6 @@ fn main() -> ! {
loop {
sniffer.send_raw_frame(false, beacon, false).unwrap();
delay.delay(100.millis());
delay.delay(Duration::from_millis(100));
}
}

View File

@ -73,7 +73,7 @@ fn main() -> ! {
let mut wifi = peripherals.WIFI;
let (iface, device, mut controller) =
create_network_interface(&init, &mut wifi, WifiApDevice).unwrap();
let now = || time::now().duration_since_epoch().to_millis();
let now = || time::Instant::now().duration_since_epoch().as_millis();
let mut socket_set_entries: [SocketStorage; 3] = Default::default();
let socket_set = SocketSet::new(&mut socket_set_entries[..]);
@ -129,7 +129,7 @@ fn main() -> ! {
println!("Connected");
let mut time_out = false;
let deadline = time::now() + Duration::secs(20);
let deadline = time::Instant::now() + Duration::from_secs(20);
let mut buffer = [0u8; 1024];
let mut pos = 0;
while let Ok(len) = socket.read(&mut buffer[pos..]) {
@ -143,7 +143,7 @@ fn main() -> ! {
pos += len;
if time::now() > deadline {
if time::Instant::now() > deadline {
println!("Timeout");
time_out = true;
break;
@ -172,8 +172,8 @@ fn main() -> ! {
println!();
}
let deadline = time::now() + Duration::secs(5);
while time::now() < deadline {
let start = time::Instant::now();
while start.elapsed() < Duration::from_secs(5) {
socket.work();
}
}

View File

@ -70,7 +70,7 @@ fn main() -> ! {
mut controller,
} = create_ap_sta_network_interface(&init, wifi).unwrap();
let now = || time::now().duration_since_epoch().to_millis();
let now = || time::Instant::now().duration_since_epoch().as_millis();
let mut ap_socket_set_entries: [SocketStorage; 3] = Default::default();
let ap_socket_set = SocketSet::new(&mut ap_socket_set_entries[..]);
let mut ap_stack = Stack::new(ap_interface, ap_device, ap_socket_set, now, rng.random());
@ -154,7 +154,7 @@ fn main() -> ! {
println!("Connected");
let mut time_out = false;
let deadline = time::now() + Duration::secs(20);
let deadline = time::Instant::now() + Duration::from_secs(20);
let mut buffer = [0u8; 1024];
let mut pos = 0;
loop {
@ -173,7 +173,7 @@ fn main() -> ! {
break;
}
if time::now() > deadline {
if time::Instant::now() > deadline {
println!("Timeout");
time_out = true;
break;
@ -193,7 +193,7 @@ fn main() -> ! {
.unwrap();
sta_socket.flush().unwrap();
let deadline = time::now() + Duration::secs(20);
let deadline = time::Instant::now() + Duration::from_secs(20);
loop {
let mut buffer = [0u8; 512];
if let Ok(len) = sta_socket.read(&mut buffer) {
@ -203,7 +203,7 @@ fn main() -> ! {
break;
}
if time::now() > deadline {
if time::Instant::now() > deadline {
println!("Timeout");
break;
}
@ -219,8 +219,8 @@ fn main() -> ! {
println!();
}
let deadline = time::now() + Duration::secs(5);
while time::now() < deadline {
let start = time::Instant::now();
while start.elapsed() < Duration::from_secs(5) {
ap_socket.work();
}
}

View File

@ -49,7 +49,7 @@ const SSID: &str = env!("SSID");
const PASSWORD: &str = env!("PASSWORD");
const HOST_IP: &str = env!("HOST_IP");
const TEST_DURATION: Duration = Duration::secs(15);
const TEST_DURATION: Duration = Duration::from_secs(15);
const RX_BUFFER_SIZE: usize = 16384;
const TX_BUFFER_SIZE: usize = 16384;
const IO_BUFFER_SIZE: usize = 1024;
@ -87,7 +87,7 @@ fn main() -> ! {
}]);
socket_set.add(dhcp_socket);
let now = || time::now().duration_since_epoch().to_millis();
let now = || time::Instant::now().duration_since_epoch().as_millis();
let stack = Stack::new(iface, device, socket_set, now, rng.random());
let client_config = Configuration::Client(ClientConfiguration {
@ -170,7 +170,7 @@ fn test_download<'a, D: smoltcp::phy::Device>(
let mut buf = [0; IO_BUFFER_SIZE];
let mut total = 0;
let deadline = time::now() + TEST_DURATION;
let deadline = time::Instant::now() + TEST_DURATION;
loop {
socket.work();
if let Ok(len) = socket.read(&mut buf) {
@ -179,12 +179,12 @@ fn test_download<'a, D: smoltcp::phy::Device>(
break;
}
if time::now() > deadline {
if time::Instant::now() > deadline {
break;
}
}
let kbps = (total + 512) / 1024 / TEST_DURATION.to_secs();
let kbps = (total + 512) / 1024 / TEST_DURATION.as_secs();
println!("download: {} kB/s", kbps);
socket.disconnect();
@ -204,7 +204,7 @@ fn test_upload<'a, D: smoltcp::phy::Device>(
let buf = [0; IO_BUFFER_SIZE];
let mut total = 0;
let deadline = time::now() + TEST_DURATION;
let deadline = time::Instant::now() + TEST_DURATION;
loop {
socket.work();
if let Ok(len) = socket.write(&buf) {
@ -213,12 +213,12 @@ fn test_upload<'a, D: smoltcp::phy::Device>(
break;
}
if time::now() > deadline {
if time::Instant::now() > deadline {
break;
}
}
let kbps = (total + 512) / 1024 / TEST_DURATION.to_secs();
let kbps = (total + 512) / 1024 / TEST_DURATION.as_secs();
println!("upload: {} kB/s", kbps);
socket.disconnect();
@ -239,7 +239,7 @@ fn test_upload_download<'a, D: smoltcp::phy::Device>(
let mut rx_buf = [0; IO_BUFFER_SIZE];
let mut total = 0;
let deadline = time::now() + TEST_DURATION;
let deadline = time::Instant::now() + TEST_DURATION;
loop {
socket.work();
if let Err(_) = socket.write(&tx_buf) {
@ -254,12 +254,12 @@ fn test_upload_download<'a, D: smoltcp::phy::Device>(
break;
}
if time::now() > deadline {
if time::Instant::now() > deadline {
break;
}
}
let kbps = (total + 512) / 1024 / TEST_DURATION.to_secs();
let kbps = (total + 512) / 1024 / TEST_DURATION.as_secs();
println!("upload+download: {} kB/s", kbps);
socket.disconnect();

View File

@ -65,7 +65,7 @@ fn main() -> ! {
let mut bluetooth = peripherals.BT;
let now = || time::now().duration_since_epoch().to_millis();
let now = || time::Instant::now().duration_since_epoch().as_millis();
loop {
let connector = BleConnector::new(&init, &mut bluetooth);
let hci = HciConnector::new(connector, now);

View File

@ -104,7 +104,7 @@ fn main() -> ! {
}]);
socket_set.add(dhcp_socket);
let now = || time::now().duration_since_epoch().to_millis();
let now = || time::Instant::now().duration_since_epoch().as_millis();
let stack = Stack::new(iface, device, socket_set, now, rng.random());
let client_config = Configuration::Client(ClientConfiguration {
@ -185,13 +185,13 @@ fn main() -> ! {
.unwrap();
socket.flush().unwrap();
let deadline = time::now() + Duration::secs(20);
let deadline = time::Instant::now() + Duration::from_secs(20);
let mut buffer = [0u8; 128];
while let Ok(len) = socket.read(&mut buffer) {
let to_print = unsafe { core::str::from_utf8_unchecked(&buffer[..len]) };
print!("{}", to_print);
if time::now() > deadline {
if time::Instant::now() > deadline {
println!("Timeout");
break;
}
@ -200,8 +200,8 @@ fn main() -> ! {
socket.disconnect();
let deadline = time::now() + Duration::secs(5);
while time::now() < deadline {
let deadline = time::Instant::now() + Duration::from_secs(5);
while time::Instant::now() < deadline {
socket.work();
}
}

View File

@ -64,7 +64,7 @@ fn main() -> ! {
}]);
socket_set.add(dhcp_socket);
let now = || time::now().duration_since_epoch().to_millis();
let now = || time::Instant::now().duration_since_epoch().as_millis();
let stack = Stack::new(iface, device, socket_set, now, rng.random());
let client_config = Configuration::Client(ClientConfiguration {

View File

@ -77,7 +77,7 @@ fn main() -> ! {
}]);
socket_set.add(dhcp_socket);
let now = || time::now().duration_since_epoch().to_millis();
let now = || time::Instant::now().duration_since_epoch().as_millis();
let stack = Stack::new(iface, device, socket_set, now, rng.random());
let client_config = Configuration::Client(ClientConfiguration {
@ -146,13 +146,13 @@ fn main() -> ! {
.unwrap();
socket.flush().unwrap();
let deadline = time::now() + Duration::secs(20);
let deadline = time::Instant::now() + Duration::from_secs(20);
let mut buffer = [0u8; 512];
while let Ok(len) = socket.read(&mut buffer) {
let to_print = unsafe { core::str::from_utf8_unchecked(&buffer[..len]) };
print!("{}", to_print);
if time::now() > deadline {
if time::Instant::now() > deadline {
println!("Timeout");
break;
}
@ -161,8 +161,8 @@ fn main() -> ! {
socket.disconnect();
let deadline = time::now() + Duration::secs(5);
while time::now() < deadline {
let deadline = time::Instant::now() + Duration::from_secs(5);
while time::Instant::now() < deadline {
socket.work();
}
}

View File

@ -91,7 +91,7 @@ async fn main(_spawner: Spawner) -> ! {
let connector = BleConnector::new(&init, &mut bluetooth);
let now = || time::now().duration_since_epoch().to_millis();
let now = || time::Instant::now().duration_since_epoch().as_millis();
let mut ble = Ble::new(connector, now);
println!("Connector created");

View File

@ -45,7 +45,7 @@ fn main() -> ! {
println!("esp-now version {}", esp_now.version().unwrap());
let mut next_send_time = time::now() + Duration::secs(5);
let mut next_send_time = time::Instant::now() + Duration::from_secs(5);
loop {
let r = esp_now.receive();
if let Some(r) = r {
@ -70,8 +70,8 @@ fn main() -> ! {
}
}
if time::now() >= next_send_time {
next_send_time = time::now() + Duration::secs(5);
if time::Instant::now() >= next_send_time {
next_send_time = time::Instant::now() + Duration::from_secs(5);
println!("Send");
let status = esp_now
.send(&BROADCAST_ADDRESS, b"0123456789")

View File

@ -64,7 +64,7 @@ fn main() -> ! {
let mut socket_set_entries: [SocketStorage; 3] = Default::default();
let socket_set = SocketSet::new(&mut socket_set_entries[..]);
let now = || time::now().duration_since_epoch().to_millis();
let now = || time::Instant::now().duration_since_epoch().as_millis();
let mut stack = Stack::new(iface, device, socket_set, now, rng.random());
let client_config = Configuration::Client(ClientConfiguration {
@ -143,7 +143,7 @@ fn main() -> ! {
println!("Connected");
let mut time_out = false;
let deadline = time::now() + Duration::secs(20);
let deadline = time::Instant::now() + Duration::from_secs(20);
let mut buffer = [0u8; 1024];
let mut pos = 0;
while let Ok(len) = socket.read(&mut buffer[pos..]) {
@ -157,7 +157,7 @@ fn main() -> ! {
pos += len;
if time::now() > deadline {
if time::Instant::now() > deadline {
println!("Timeout");
time_out = true;
break;
@ -185,8 +185,8 @@ fn main() -> ! {
println!();
}
let deadline = time::now() + Duration::secs(5);
while time::now() < deadline {
let deadline = time::Instant::now() + Duration::from_secs(5);
while time::Instant::now() < deadline {
socket.work();
}
}

View File

@ -236,7 +236,6 @@ elliptic-curve = { version = "0.13.8", default-features = false, features =
embassy-executor = { version = "0.7.0", default-features = false }
# Add the `embedded-test/defmt` feature for more verbose testing
embedded-test = { version = "0.6.0", default-features = false, features = ["embassy", "external-executor"] }
fugit = "0.3.7"
hex-literal = "0.4.1"
nb = "1.1.0"
p192 = { version = "0.13.0", default-features = false, features = ["arithmetic"] }

View File

@ -29,58 +29,57 @@ mod tests {
#[test]
fn delay_ns(mut ctx: Context) {
let t1 = esp_hal::time::now();
ctx.delay.delay_ns(600_000_000);
let t2 = esp_hal::time::now();
let t1 = esp_hal::time::Instant::now();
ctx.delay.delay_ns(600_000);
let t2 = esp_hal::time::Instant::now();
assert!(t2 > t1);
assert!(
(t2 - t1).to_nanos() >= 600_000_000u64,
(t2 - t1).as_micros() >= 600u64,
"diff: {:?}",
(t2 - t1).to_nanos()
(t2 - t1).as_micros()
);
}
#[test]
fn delay_700millis(ctx: Context) {
let t1 = esp_hal::time::now();
ctx.delay.delay_millis(700);
let t2 = esp_hal::time::now();
fn delay_70millis(ctx: Context) {
let t1 = esp_hal::time::Instant::now();
ctx.delay.delay_millis(70);
let t2 = esp_hal::time::Instant::now();
assert!(t2 > t1);
assert!(
(t2 - t1).to_millis() >= 700u64,
(t2 - t1).as_millis() >= 70u64,
"diff: {:?}",
(t2 - t1).to_millis()
(t2 - t1).as_millis()
);
}
#[test]
fn delay_1_500_000us(mut ctx: Context) {
let t1 = esp_hal::time::now();
ctx.delay.delay_us(1_500_000);
let t2 = esp_hal::time::now();
fn delay_1_500us(mut ctx: Context) {
let t1 = esp_hal::time::Instant::now();
ctx.delay.delay_us(1_500);
let t2 = esp_hal::time::Instant::now();
assert!(t2 > t1);
assert!(
(t2 - t1).to_micros() >= 1_500_000u64,
(t2 - t1).as_micros() >= 1_500u64,
"diff: {:?}",
(t2 - t1).to_micros()
(t2 - t1).as_micros()
);
}
#[test]
#[timeout(5)]
fn delay_3_000ms(mut ctx: Context) {
let t1 = esp_hal::time::now();
ctx.delay.delay_ms(3000);
let t2 = esp_hal::time::now();
fn delay_3_00ms(mut ctx: Context) {
let t1 = esp_hal::time::Instant::now();
ctx.delay.delay_ms(300);
let t2 = esp_hal::time::Instant::now();
assert!(t2 > t1);
assert!(
(t2 - t1).to_millis() >= 3000u64,
(t2 - t1).as_millis() >= 300u64,
"diff: {:?}",
(t2 - t1).to_millis()
(t2 - t1).as_millis()
);
}
}

View File

@ -24,16 +24,16 @@ struct Context {
async fn test_async_delay_ns(mut timer: impl DelayNs, duration: u32) {
for i in 1..5 {
let t1 = esp_hal::time::now();
let t1 = esp_hal::time::Instant::now();
timer.delay_ns(duration).await;
let t2 = esp_hal::time::now();
let t2 = esp_hal::time::Instant::now();
assert!(t2 > t1);
assert!(
(t2 - t1).to_nanos() >= duration as u64,
(t2 - t1).as_micros() >= duration.div_ceil(1000) as u64,
"diff[{}]: {:?} >= {}",
i,
(t2 - t1).to_nanos(),
(t2 - t1).as_micros(),
duration
);
}
@ -41,30 +41,30 @@ async fn test_async_delay_ns(mut timer: impl DelayNs, duration: u32) {
async fn test_async_delay_us(mut timer: impl DelayNs, duration: u32) {
for _ in 1..5 {
let t1 = esp_hal::time::now();
let t1 = esp_hal::time::Instant::now();
timer.delay_us(duration).await;
let t2 = esp_hal::time::now();
let t2 = esp_hal::time::Instant::now();
assert!(t2 > t1);
assert!(
(t2 - t1).to_nanos() >= duration as u64,
(t2 - t1).as_micros() >= duration as u64,
"diff: {:?}",
(t2 - t1).to_nanos()
(t2 - t1).as_micros()
);
}
}
async fn test_async_delay_ms(mut timer: impl DelayNs, duration: u32) {
for _ in 1..5 {
let t1 = esp_hal::time::now();
let t1 = esp_hal::time::Instant::now();
timer.delay_ms(duration).await;
let t2 = esp_hal::time::now();
let t2 = esp_hal::time::Instant::now();
assert!(t2 > t1);
assert!(
(t2 - t1).to_nanos() >= duration as u64,
(t2 - t1).as_millis() >= duration as u64,
"diff: {:?}",
(t2 - t1).to_nanos()
(t2 - t1).as_millis()
);
}
}

View File

@ -20,7 +20,7 @@ use esp_hal::{
master::{Config, Spi},
Mode,
},
time::RateExtU32,
time::Rate,
timer::AnyTimer,
Blocking,
};
@ -130,7 +130,7 @@ mod test {
let mut spi = Spi::new(
peripherals.SPI2,
Config::default()
.with_frequency(10000.kHz())
.with_frequency(Rate::from_khz(10000))
.with_mode(Mode::_0),
)
.unwrap()
@ -144,7 +144,7 @@ mod test {
let other_peripheral = Spi::new(
peripherals.SPI3,
Config::default()
.with_frequency(10000.kHz())
.with_frequency(Rate::from_khz(10000))
.with_mode(Mode::_0),
)
.unwrap()
@ -158,7 +158,7 @@ mod test {
peripherals.I2S0,
esp_hal::i2s::master::Standard::Philips,
esp_hal::i2s::master::DataFormat::Data8Channel8,
8u32.kHz(),
Rate::from_khz(8),
dma_channel2,
rx_descriptors,
tx_descriptors,
@ -234,7 +234,7 @@ mod test {
let mut spi = Spi::new(
peripherals.spi,
Config::default()
.with_frequency(100.kHz())
.with_frequency(Rate::from_khz(100))
.with_mode(Mode::_0),
)
.unwrap()

View File

@ -16,7 +16,7 @@ use esp_hal::{
};
use esp_hal::{
peripherals::Peripherals,
time::ExtU64,
time,
timer::{timg::TimerGroup, OneShotTimer, PeriodicTimer},
};
#[cfg(not(feature = "esp32"))]
@ -49,63 +49,63 @@ mod test_cases {
use super::*;
pub async fn run_test_one_shot_async() {
let t1 = esp_hal::time::now();
let t1 = esp_hal::time::Instant::now();
Timer::after_millis(50).await;
Timer::after_millis(30).await;
let t2 = esp_hal::time::now();
let t2 = esp_hal::time::Instant::now();
assert!(t2 > t1, "t2: {:?}, t1: {:?}", t2, t1);
assert!(
(t2 - t1).to_millis() >= 80u64,
(t2 - t1).as_millis() >= 80u64,
"diff: {:?}",
(t2 - t1).to_millis()
(t2 - t1).as_millis()
);
}
pub fn run_test_periodic_timer<T: esp_hal::timer::Timer>(timer: impl Peripheral<P = T>) {
let mut periodic = PeriodicTimer::new(timer);
let t1 = esp_hal::time::now();
periodic.start(100.millis()).unwrap();
let t1 = time::Instant::now();
periodic.start(time::Duration::from_millis(100)).unwrap();
periodic.wait();
let t2 = esp_hal::time::now();
let t2 = time::Instant::now();
assert!(t2 > t1, "t2: {:?}, t1: {:?}", t2, t1);
assert!(
(t2 - t1).to_millis() >= 100u64,
(t2 - t1).as_millis() >= 100u64,
"diff: {:?}",
(t2 - t1).to_millis()
(t2 - t1).as_millis()
);
}
pub fn run_test_oneshot_timer<T: esp_hal::timer::Timer>(timer: impl Peripheral<P = T>) {
let mut timer = OneShotTimer::new(timer);
let t1 = esp_hal::time::now();
let t1 = esp_hal::time::Instant::now();
timer.delay_millis(50);
let t2 = esp_hal::time::now();
let t2 = esp_hal::time::Instant::now();
assert!(t2 > t1, "t2: {:?}, t1: {:?}", t2, t1);
assert!(
(t2 - t1).to_millis() >= 50u64,
(t2 - t1).as_millis() >= 50u64,
"diff: {:?}",
(t2 - t1).to_millis()
(t2 - t1).as_millis()
);
}
pub async fn run_join_test() {
let t1 = esp_hal::time::now();
let t1 = esp_hal::time::Instant::now();
embassy_futures::join::join(Timer::after_millis(50), Timer::after_millis(30)).await;
Timer::after_millis(50).await;
let t2 = esp_hal::time::now();
let t2 = esp_hal::time::Instant::now();
assert!(t2 > t1, "t2: {:?}, t1: {:?}", t2, t1);
assert!(
(t2 - t1).to_millis() >= 100u64,
(t2 - t1).as_millis() >= 100u64,
"diff: {:?}",
(t2 - t1).to_millis()
(t2 - t1).as_millis()
);
}
}
@ -219,17 +219,17 @@ mod test {
let outcome = async {
let mut ticker = Ticker::every(Duration::from_millis(30));
let t1 = esp_hal::time::now();
let t1 = esp_hal::time::Instant::now();
ticker.next().await;
ticker.next().await;
ticker.next().await;
let t2 = esp_hal::time::now();
let t2 = esp_hal::time::Instant::now();
assert!(t2 > t1, "t2: {:?}, t1: {:?}", t2, t1);
assert!(
(t2 - t1).to_micros() >= 85000u64,
(t2 - t1).as_micros() >= 85000u64,
"diff: {:?}",
(t2 - t1).to_micros()
(t2 - t1).as_micros()
);
};
@ -254,18 +254,18 @@ mod test {
// We are retrying 5 times because probe-rs polling RTT may introduce some
// jitter.
for _ in 0..5 {
let t1 = esp_hal::time::now();
let t1 = esp_hal::time::Instant::now();
let mut ticker = Ticker::every(Duration::from_hz(100_000));
for _ in 0..2000 {
ticker.next().await;
}
let t2 = esp_hal::time::now();
let t2 = esp_hal::time::Instant::now();
assert!(t2 > t1, "t2: {:?}, t1: {:?}", t2, t1);
let duration = (t2 - t1).to_micros();
let duration = (t2 - t1).as_micros();
assert!(duration >= 19000, "diff: {:?}", (t2 - t1).to_micros());
assert!(duration >= 19000, "diff: {:?}", (t2 - t1).as_micros());
if duration <= 21000 {
return;
}

View File

@ -1,4 +1,4 @@
//! time::now Test
//! time::Instant::now Test
//% CHIPS: esp32 esp32c2 esp32c3 esp32c6 esp32h2 esp32s2 esp32s3
//% FEATURES: unstable
@ -14,9 +14,9 @@ struct Context {
}
fn time_moves_forward_during<F: FnOnce(Context)>(ctx: Context, f: F) {
let t1 = esp_hal::time::now();
let t1 = esp_hal::time::Instant::now();
f(ctx);
let t2 = esp_hal::time::now();
let t2 = esp_hal::time::Instant::now();
assert!(t2 > t1);
}
@ -37,12 +37,12 @@ mod tests {
#[test]
fn test_current_time(ctx: Context) {
let t1 = esp_hal::time::now();
let t1 = esp_hal::time::Instant::now();
ctx.delay.delay_millis(500);
let t2 = esp_hal::time::now();
let t2 = esp_hal::time::Instant::now();
assert!(t2 > t1);
assert!((t2 - t1).to_millis() >= 500u64);
assert!((t2 - t1).as_millis() >= 500u64);
}
#[cfg(systimer)]

View File

@ -16,7 +16,7 @@ use esp_hal::{
gpio::{AnyPin, NoPin, Pin},
i2s::master::{DataFormat, I2s, I2sTx, Standard},
peripherals::I2S0,
time::RateExtU32,
time::Rate,
Async,
};
use hil_test as _;
@ -139,7 +139,7 @@ mod tests {
ctx.i2s,
Standard::Philips,
DataFormat::Data16Channel16,
16000.Hz(),
Rate::from_hz(16000),
ctx.dma_channel,
rx_descriptors,
tx_descriptors,
@ -192,7 +192,7 @@ mod tests {
ctx.i2s,
Standard::Philips,
DataFormat::Data16Channel16,
16000.Hz(),
Rate::from_hz(16000),
ctx.dma_channel,
rx_descriptors,
tx_descriptors,
@ -301,7 +301,7 @@ mod tests {
ctx.i2s,
Standard::Philips,
DataFormat::Data16Channel16,
16000.Hz(),
Rate::from_hz(16000),
ctx.dma_channel,
rx_descriptors,
tx_descriptors,
@ -331,7 +331,7 @@ mod tests {
ctx.i2s,
Standard::Philips,
DataFormat::Data16Channel16,
16000.Hz(),
Rate::from_hz(16000),
ctx.dma_channel,
rx_descriptors,
tx_descriptors,

View File

@ -10,7 +10,7 @@ use esp_hal::{
gpio::NoPin,
i2s::parallel::{I2sParallel, TxSixteenBits},
peripherals::I2S0,
time::RateExtU32,
time::Rate,
};
use hil_test as _;
@ -46,7 +46,8 @@ mod tests {
NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin,
NoPin, NoPin, NoPin, NoPin,
);
let i2s = I2sParallel::new(ctx.i2s, ctx.dma_channel, 20.MHz(), pins, NoPin).into_async();
let i2s = I2sParallel::new(ctx.i2s, ctx.dma_channel, Rate::from_mhz(20), pins, NoPin)
.into_async();
// Try sending an empty buffer, as an edge case
let tx_buf = esp_hal::dma_tx_buffer!(4096).unwrap();

View File

@ -11,7 +11,7 @@ use esp_hal::{
config::{WatchdogConfig, WatchdogStatus},
delay::Delay,
rtc_cntl::Rtc,
time::ExtU64,
time::Duration,
timer::timg::TimerGroup,
Config,
};
@ -24,11 +24,12 @@ mod tests {
#[test]
fn test_feeding_timg0_wdt() {
let peripherals = esp_hal::init(Config::default().with_watchdog(
WatchdogConfig::default().with_timg0(WatchdogStatus::Enabled(
fugit::MicrosDurationU64::millis(500),
)),
));
let peripherals = esp_hal::init(
Config::default().with_watchdog(
WatchdogConfig::default()
.with_timg0(WatchdogStatus::Enabled(Duration::from_millis(500))),
),
);
let timg0 = TimerGroup::new(peripherals.TIMG0);
let mut wdt0 = timg0.wdt;
@ -36,18 +37,19 @@ mod tests {
for _ in 0..4 {
wdt0.feed();
delay.delay(250.millis());
delay.delay(Duration::from_millis(250));
}
}
#[test]
#[cfg(timg1)]
fn test_feeding_timg1_wdt() {
let peripherals = esp_hal::init(Config::default().with_watchdog(
WatchdogConfig::default().with_timg1(WatchdogStatus::Enabled(
fugit::MicrosDurationU64::millis(500),
)),
));
let peripherals = esp_hal::init(
Config::default().with_watchdog(
WatchdogConfig::default()
.with_timg1(WatchdogStatus::Enabled(Duration::from_millis(500))),
),
);
let timg1 = TimerGroup::new(peripherals.TIMG1);
let mut wdt1 = timg1.wdt;
@ -55,7 +57,7 @@ mod tests {
for _ in 0..4 {
wdt1.feed();
delay.delay(250.millis());
delay.delay(Duration::from_millis(250));
}
}
@ -65,9 +67,8 @@ mod tests {
Config::default()
.with_cpu_clock(CpuClock::max())
.with_watchdog(
WatchdogConfig::default().with_timg0(WatchdogStatus::Enabled(
fugit::MicrosDurationU64::millis(500),
)),
WatchdogConfig::default()
.with_timg0(WatchdogStatus::Enabled(Duration::from_millis(500))),
),
);
@ -77,24 +78,25 @@ mod tests {
for _ in 0..4 {
wdt0.feed();
delay.delay(250.millis());
delay.delay(Duration::from_millis(250));
}
}
#[test]
#[timeout(4)]
fn test_feeding_rtc_wdt() {
let peripherals = esp_hal::init(Config::default().with_watchdog(
WatchdogConfig::default().with_rwdt(WatchdogStatus::Enabled(
fugit::MicrosDurationU64::millis(3000),
)),
));
let peripherals = esp_hal::init(
Config::default().with_watchdog(
WatchdogConfig::default()
.with_rwdt(WatchdogStatus::Enabled(Duration::from_millis(3000))),
),
);
let mut rtc = Rtc::new(peripherals.LPWR);
let delay = Delay::new();
rtc.rwdt.feed();
delay.delay(2500.millis());
delay.delay(Duration::from_millis(2500));
}
#[test]
@ -102,6 +104,6 @@ mod tests {
esp_hal::init(Config::default());
let delay = Delay::new();
delay.delay(2000.millis());
delay.delay(Duration::from_millis(2000));
}
}

View File

@ -22,8 +22,8 @@ use esp_hal::{
LcdCam,
},
peripherals::Peripherals,
time::Rate,
};
use fugit::RateExtU32;
use hil_test as _;
struct Context {
@ -78,7 +78,7 @@ mod tests {
polarity: Polarity::IdleHigh,
phase: Phase::ShiftLow,
})
.with_frequency(500u32.kHz())
.with_frequency(Rate::from_khz(500))
.with_format(Format {
enable_2byte_mode: false,
..Default::default()
@ -121,7 +121,7 @@ mod tests {
lcd_cam.cam,
rx_channel,
RxEightBits::new(d0_in, d1_in, d2_in, d3_in, d4_in, d5_in, d6_in, d7_in),
cam::Config::default().with_frequency(1u32.MHz()),
cam::Config::default().with_frequency(Rate::from_mhz(1)),
)
.unwrap()
.with_ctrl_pins_and_de(vsync_in, hsync_in, de_in)

View File

@ -19,7 +19,7 @@ use esp_hal::{
channel::{CtrlMode, EdgeMode},
Pcnt,
},
time::RateExtU32,
time::Rate,
Blocking,
};
use hil_test as _;
@ -80,7 +80,7 @@ mod tests {
ctx.lcd_cam.lcd,
ctx.dma,
pins,
Config::default().with_frequency(20.MHz()),
Config::default().with_frequency(Rate::from_mhz(20)),
)
.unwrap();
@ -143,7 +143,7 @@ mod tests {
ctx.lcd_cam.lcd,
ctx.dma,
pins,
Config::default().with_frequency(20.MHz()),
Config::default().with_frequency(Rate::from_mhz(20)),
)
.unwrap()
.with_cs(cs_signal)
@ -265,7 +265,7 @@ mod tests {
ctx.lcd_cam.lcd,
ctx.dma,
pins,
Config::default().with_frequency(20.MHz()),
Config::default().with_frequency(Rate::from_mhz(20)),
)
.unwrap()
.with_cs(cs_signal)

View File

@ -14,7 +14,7 @@ use esp_hal::{
lcd::i8080::{Command, Config, TxEightBits, I8080},
LcdCam,
},
time::RateExtU32,
time::Rate,
Async,
};
use hil_test as _;
@ -55,7 +55,7 @@ mod tests {
ctx.lcd_cam.lcd,
ctx.dma,
pins,
Config::default().with_frequency(20.MHz()),
Config::default().with_frequency(Rate::from_mhz(20)),
)
.unwrap();

View File

@ -23,7 +23,7 @@ use esp_hal::{
TxPinConfigWithValidPin,
},
peripherals::PARL_IO,
time::RateExtU32,
time::Rate,
};
use hil_test as _;
@ -84,7 +84,7 @@ mod tests {
let clock_out_pin = ClkOutPin::new(clock_tx);
let mut clock_in_pin = RxClkInPin::new(clock_rx, SampleEdge::Normal);
let pio = ParlIoFullDuplex::new(ctx.parl_io, ctx.dma_channel, 40.MHz()).unwrap();
let pio = ParlIoFullDuplex::new(ctx.parl_io, ctx.dma_channel, Rate::from_mhz(40)).unwrap();
let pio_tx = pio
.tx

View File

@ -29,7 +29,7 @@ use esp_hal::{
Pcnt,
},
peripherals::PARL_IO,
time::RateExtU32,
time::Rate,
};
use hil_test as _;
@ -89,7 +89,7 @@ mod tests {
let mut pins = TxPinConfigIncludingValidPin::new(pins);
let mut clock_pin = ClkOutPin::new(ctx.clock);
let pio = ParlIoTxOnly::new(ctx.parl_io, ctx.dma_channel, 10.MHz()).unwrap();
let pio = ParlIoTxOnly::new(ctx.parl_io, ctx.dma_channel, Rate::from_mhz(10)).unwrap();
let mut pio = pio
.tx
@ -151,7 +151,7 @@ mod tests {
let mut clock_pin = ClkOutPin::new(ctx.clock);
let pio = ParlIoTxOnly::new(ctx.parl_io, ctx.dma_channel, 10.MHz()).unwrap();
let pio = ParlIoTxOnly::new(ctx.parl_io, ctx.dma_channel, Rate::from_mhz(10)).unwrap();
let mut pio = pio
.tx

View File

@ -29,7 +29,7 @@ use esp_hal::{
Pcnt,
},
peripherals::PARL_IO,
time::RateExtU32,
time::Rate,
};
use hil_test as _;
@ -88,7 +88,7 @@ mod tests {
let mut pins = TxPinConfigIncludingValidPin::new(pins);
let mut clock_pin = ClkOutPin::new(ctx.clock);
let pio = ParlIoTxOnly::new(ctx.parl_io, ctx.dma_channel, 10.MHz())
let pio = ParlIoTxOnly::new(ctx.parl_io, ctx.dma_channel, Rate::from_mhz(10))
.unwrap()
.into_async();
@ -154,7 +154,7 @@ mod tests {
let mut clock_pin = ClkOutPin::new(ctx.clock);
let pio = ParlIoTxOnly::new(ctx.parl_io, ctx.dma_channel, 10.MHz())
let pio = ParlIoTxOnly::new(ctx.parl_io, ctx.dma_channel, Rate::from_mhz(10))
.unwrap()
.into_async();

View File

@ -17,7 +17,7 @@ use esp_hal::{
DataMode,
Mode,
},
time::RateExtU32,
time::Rate,
Blocking,
};
use hil_test as _;
@ -213,7 +213,7 @@ mod tests {
let spi = Spi::new(
peripherals.SPI2,
Config::default()
.with_frequency(100.kHz())
.with_frequency(Rate::from_khz(100))
.with_mode(Mode::_0),
)
.unwrap();

View File

@ -9,7 +9,7 @@
use esp_hal::{
gpio::Level,
rmt::{PulseCode, Rmt, RxChannel, RxChannelConfig, TxChannel, TxChannelConfig},
time::RateExtU32,
time::Rate,
};
use hil_test as _;
@ -29,9 +29,9 @@ mod tests {
cfg_if::cfg_if! {
if #[cfg(feature = "esp32h2")] {
let freq = 32.MHz();
let freq = Rate::from_mhz(32);
} else {
let freq = 80.MHz();
let freq = Rate::from_mhz(80);
}
};
@ -98,9 +98,9 @@ mod tests {
cfg_if::cfg_if! {
if #[cfg(feature = "esp32h2")] {
let freq = 32.MHz();
let freq = Rate::from_mhz(32);
} else {
let freq = 80.MHz();
let freq = Rate::from_mhz(80);
}
};

View File

@ -13,9 +13,9 @@ use embedded_hal::spi::SpiBus;
use embedded_hal_async::spi::SpiBus as SpiBusAsync;
use esp_hal::{
spi::master::{Config, Spi},
time::Rate,
Blocking,
};
use fugit::RateExtU32;
use hil_test as _;
cfg_if::cfg_if! {
@ -103,11 +103,14 @@ mod tests {
// Need to set miso first so that mosi can overwrite the
// output connection (because we are using the same pin to loop back)
let spi = Spi::new(peripherals.SPI2, Config::default().with_frequency(10.MHz()))
.unwrap()
.with_sck(peripherals.GPIO0)
.with_miso(miso)
.with_mosi(mosi);
let spi = Spi::new(
peripherals.SPI2,
Config::default().with_frequency(Rate::from_mhz(10)),
)
.unwrap()
.with_sck(peripherals.GPIO0)
.with_miso(miso)
.with_mosi(mosi);
cfg_if::cfg_if! {
if #[cfg(feature = "unstable")] {
@ -233,7 +236,7 @@ mod tests {
let mut spi = ctx.spi.into_async();
// Slow down SCLK so that transferring the buffer takes a while.
spi.apply_config(&Config::default().with_frequency(80.kHz()))
spi.apply_config(&Config::default().with_frequency(Rate::from_khz(80)))
.expect("Apply config failed");
SpiBus::write(&mut spi, &write[..]).expect("Sync write failed");
@ -705,7 +708,7 @@ mod tests {
// This means that without working cancellation, the test case should
// fail.
ctx.spi
.apply_config(&Config::default().with_frequency(80.kHz()))
.apply_config(&Config::default().with_frequency(Rate::from_khz(80)))
.unwrap();
// Set up a large buffer that would trigger a timeout
@ -728,7 +731,7 @@ mod tests {
fn can_transmit_after_cancel(mut ctx: Context) {
// Slow down. At 80kHz, the transfer is supposed to take a bit over 3 seconds.
ctx.spi
.apply_config(&Config::default().with_frequency(80.kHz()))
.apply_config(&Config::default().with_frequency(Rate::from_khz(80)))
.unwrap();
// Set up a large buffer that would trigger a timeout
@ -745,7 +748,7 @@ mod tests {
transfer.cancel();
(spi, (dma_rx_buf, dma_tx_buf)) = transfer.wait();
spi.apply_config(&Config::default().with_frequency(10.MHz()))
spi.apply_config(&Config::default().with_frequency(Rate::from_mhz(10)))
.unwrap();
let transfer = spi

View File

@ -15,7 +15,7 @@ use esp_hal::{
DataMode,
Mode,
},
time::RateExtU32,
time::Rate,
Blocking,
};
use hil_test as _;
@ -50,7 +50,7 @@ mod tests {
let spi = Spi::new(
peripherals.SPI2,
Config::default()
.with_frequency(100.kHz())
.with_frequency(Rate::from_khz(100))
.with_mode(Mode::_0),
)
.unwrap()

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