PeripheralRef init: uart (#272)

* Add the peripheral module plus some helper macros in preparation

* peripheral macro

* Add peripheral generation macro

* Fixes after rebase

* Update the signature of Peripherals::take

* syncronise hello world example

* fmt the entire repo

Co-authored-by: Jesse Braham <jesse@beta7.io>
This commit is contained in:
Scott Mabin 2022-12-12 15:45:33 +01:00 committed by GitHub
parent 03d94a0ba2
commit 248fb356f8
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
156 changed files with 1554 additions and 702 deletions

View File

@ -55,7 +55,14 @@ fn main() {
"uart2",
]
} else if esp32c2 {
vec!["esp32c2", "riscv", "single_core", "gdma", "systimer", "timg0"]
vec![
"esp32c2",
"riscv",
"single_core",
"gdma",
"systimer",
"timg0",
]
} else if esp32c3 {
vec![
"esp32c3",

View File

@ -75,7 +75,11 @@ impl EmbassyTimer {
}
}
pub(crate) fn set_alarm(&self, alarm: embassy_time::driver::AlarmHandle, timestamp: u64) -> bool {
pub(crate) fn set_alarm(
&self,
alarm: embassy_time::driver::AlarmHandle,
timestamp: u64,
) -> bool {
critical_section::with(|cs| {
let now = Self::now();
let alarm_state = unsafe { self.alarms.borrow(cs).get_unchecked(alarm.id() as usize) };
@ -108,7 +112,7 @@ impl EmbassyTimer {
}
fn disable_interrupt(&self, id: u8) {
match id {
match id {
0 => self.alarm0.interrupt_enable(false),
1 => self.alarm1.interrupt_enable(false),
2 => self.alarm2.interrupt_enable(false),

View File

@ -68,7 +68,11 @@ impl EmbassyTimer {
}
}
pub(crate) fn set_alarm(&self, alarm: embassy_time::driver::AlarmHandle, timestamp: u64) -> bool {
pub(crate) fn set_alarm(
&self,
alarm: embassy_time::driver::AlarmHandle,
timestamp: u64,
) -> bool {
critical_section::with(|cs| {
let now = Self::now();
let alarm_state = unsafe { self.alarms.borrow(cs).get_unchecked(alarm.id() as usize) };
@ -87,7 +91,7 @@ impl EmbassyTimer {
tg.set_auto_reload(false);
tg.set_counter_active(true);
tg.set_alarm_active(true);
true
})
}

View File

@ -340,7 +340,9 @@ mod vectored {
const CPU_INTERRUPT_EDGE: u32 = 0b_0111_0000_0100_0000_0000_1100_1000_0000;
#[inline]
fn cpu_interrupt_nr_to_cpu_interrupt_handler(number: u32) -> Option<unsafe extern "C" fn(u32, save_frame: &mut Context)> {
fn cpu_interrupt_nr_to_cpu_interrupt_handler(
number: u32,
) -> Option<unsafe extern "C" fn(u32, save_frame: &mut Context)> {
use xtensa_lx_rt::*;
// we're fortunate that all esp variants use the same CPU interrupt layout
Some(match number {

View File

@ -22,15 +22,23 @@
#![cfg_attr(xtensa, feature(asm_experimental_arch))]
#[cfg(esp32)]
pub use esp32 as pac;
pub(crate) use esp32 as pac;
#[cfg(esp32c2)]
pub use esp32c2 as pac;
pub(crate) use esp32c2 as pac;
#[cfg(esp32c3)]
pub use esp32c3 as pac;
pub(crate) use esp32c3 as pac;
#[cfg(esp32s2)]
pub use esp32s2 as pac;
pub(crate) use esp32s2 as pac;
#[cfg(esp32s3)]
pub use esp32s3 as pac;
pub(crate) use esp32s3 as pac;
#[cfg_attr(esp32, path = "peripherals/esp32.rs")]
#[cfg_attr(esp32c3, path = "peripherals/esp32c3.rs")]
#[cfg_attr(esp32c2, path = "peripherals/esp32c2.rs")]
#[cfg_attr(esp32s2, path = "peripherals/esp32s2.rs")]
#[cfg_attr(esp32s3, path = "peripherals/esp32s3.rs")]
pub mod peripherals;
pub use procmacros as macros;
#[cfg(rmt)]
@ -43,9 +51,9 @@ pub use self::{
interrupt::*,
rng::Rng,
rtc_cntl::{Rtc, Rwdt},
serial::Serial,
spi::Spi,
timer::Timer,
uart::Uart,
};
pub mod analog;
@ -63,19 +71,20 @@ pub mod ledc;
pub mod mcpwm;
#[cfg(usb_otg)]
pub mod otg_fs;
pub mod peripheral;
pub mod prelude;
#[cfg(rmt)]
pub mod pulse_control;
pub mod rng;
pub mod rom;
pub mod rtc_cntl;
pub mod serial;
pub mod sha;
pub mod spi;
pub mod system;
#[cfg(systimer)]
pub mod systimer;
pub mod timer;
pub mod uart;
#[cfg(usb_serial_jtag)]
pub mod usb_serial_jtag;
#[cfg(rmt)]

View File

@ -0,0 +1,308 @@
use core::{
marker::PhantomData,
ops::{Deref, DerefMut},
};
/// An exclusive reference to a peripheral.
///
/// This is functionally the same as a `&'a mut T`. The reason for having a
/// dedicated struct is memory efficiency:
///
/// Peripheral singletons are typically either zero-sized (for concrete
/// peripehrals like `PA9` or `Spi4`) or very small (for example `AnyPin` which
/// is 1 byte). However `&mut T` is always 4 bytes for 32-bit targets, even if T
/// is zero-sized. PeripheralRef stores a copy of `T` instead, so it's the same
/// size.
///
/// but it is the size of `T` not the size
/// of a pointer. This is useful if T is a zero sized type.
pub struct PeripheralRef<'a, T> {
inner: T,
_lifetime: PhantomData<&'a mut T>,
}
impl<'a, T> PeripheralRef<'a, T> {
#[inline]
pub fn new(inner: T) -> Self {
Self {
inner,
_lifetime: PhantomData,
}
}
/// Unsafely clone (duplicate) a peripheral singleton.
///
/// # Safety
///
/// This returns an owned clone of the peripheral. You must manually ensure
/// only one copy of the peripheral is in use at a time. For example, don't
/// create two SPI drivers on `SPI1`, because they will "fight" each other.
///
/// You should strongly prefer using `reborrow()` instead. It returns a
/// `PeripheralRef` that borrows `self`, which allows the borrow checker
/// to enforce this at compile time.
pub unsafe fn clone_unchecked(&mut self) -> PeripheralRef<'a, T>
where
T: Peripheral<P = T>,
{
PeripheralRef::new(self.inner.clone_unchecked())
}
/// Reborrow into a "child" PeripheralRef.
///
/// `self` will stay borrowed until the child PeripheralRef is dropped.
pub fn reborrow(&mut self) -> PeripheralRef<'_, T>
where
T: Peripheral<P = T>,
{
// safety: we're returning the clone inside a new PeripheralRef that borrows
// self, so user code can't use both at the same time.
PeripheralRef::new(unsafe { self.inner.clone_unchecked() })
}
/// Map the inner peripheral using `Into`.
///
/// This converts from `PeripheralRef<'a, T>` to `PeripheralRef<'a, U>`,
/// using an `Into` impl to convert from `T` to `U`.
///
/// For example, this can be useful to degrade GPIO pins: converting from
/// PeripheralRef<'a, PB11>` to `PeripheralRef<'a, AnyPin>`.
#[inline]
pub fn map_into<U>(self) -> PeripheralRef<'a, U>
where
T: Into<U>,
{
PeripheralRef {
inner: self.inner.into(),
_lifetime: PhantomData,
}
}
}
impl<'a, T> Deref for PeripheralRef<'a, T> {
type Target = T;
#[inline]
fn deref(&self) -> &Self::Target {
&self.inner
}
}
impl<'a, T> DerefMut for PeripheralRef<'a, T> {
#[inline]
fn deref_mut(&mut self) -> &mut Self::Target {
&mut self.inner
}
}
/// Trait for any type that can be used as a peripheral of type `P`.
///
/// This is used in driver constructors, to allow passing either owned
/// peripherals (e.g. `TWISPI0`), or borrowed peripherals (e.g. `&mut TWISPI0`).
///
/// For example, if you have a driver with a constructor like this:
///
/// ```ignore
/// impl<'d, T: Instance> Twim<'d, T> {
/// pub fn new(
/// twim: impl Peripheral<P = T> + 'd,
/// irq: impl Peripheral<P = T::Interrupt> + 'd,
/// sda: impl Peripheral<P = impl GpioPin> + 'd,
/// scl: impl Peripheral<P = impl GpioPin> + 'd,
/// config: Config,
/// ) -> Self { .. }
/// }
/// ```
///
/// You may call it with owned peripherals, which yields an instance that can
/// live forever (`'static`):
///
/// ```ignore
/// let mut twi: Twim<'static, ...> = Twim::new(p.TWISPI0, irq, p.P0_03, p.P0_04, config);
/// ```
///
/// Or you may call it with borrowed peripherals, which yields an instance that
/// can only live for as long as the borrows last:
///
/// ```ignore
/// let mut twi: Twim<'_, ...> = Twim::new(&mut p.TWISPI0, &mut irq, &mut p.P0_03, &mut p.P0_04, config);
/// ```
///
/// # Implementation details, for HAL authors
///
/// When writing a HAL, the intended way to use this trait is to take `impl
/// Peripheral<P = ..>` in the HAL's public API (such as driver constructors),
/// calling `.into_ref()` to obtain a `PeripheralRef`, and storing that in the
/// driver struct.
///
/// `.into_ref()` on an owned `T` yields a `PeripheralRef<'static, T>`.
/// `.into_ref()` on an `&'a mut T` yields a `PeripheralRef<'a, T>`.
pub trait Peripheral: Sized + sealed::Sealed {
/// Peripheral singleton type
type P;
/// Unsafely clone (duplicate) a peripheral singleton.
///
/// # Safety
///
/// This returns an owned clone of the peripheral. You must manually ensure
/// only one copy of the peripheral is in use at a time. For example, don't
/// create two SPI drivers on `SPI1`, because they will "fight" each other.
///
/// You should strongly prefer using `into_ref()` instead. It returns a
/// `PeripheralRef`, which allows the borrow checker to enforce this at
/// compile time.
unsafe fn clone_unchecked(&mut self) -> Self::P;
/// Convert a value into a `PeripheralRef`.
///
/// When called on an owned `T`, yields a `PeripheralRef<'static, T>`.
/// When called on an `&'a mut T`, yields a `PeripheralRef<'a, T>`.
#[inline]
fn into_ref<'a>(mut self) -> PeripheralRef<'a, Self::P>
where
Self: 'a,
{
PeripheralRef::new(unsafe { self.clone_unchecked() })
}
}
impl<T: DerefMut> sealed::Sealed for T {}
pub(crate) mod sealed {
pub trait Sealed {}
}
mod peripheral_macros {
#[macro_export]
macro_rules! peripherals {
($($(#[$cfg:meta])? $name:ident),*$(,)?) => {
#[allow(non_snake_case)]
pub struct Peripherals {
$(
$(#[$cfg])?
pub $name: peripherals::$name,
)*
}
impl Peripherals {
/// Returns all the peripherals *once*
#[inline]
pub fn take() -> Self {
#[no_mangle]
static mut _ESP_HAL_DEVICE_PERIPHERALS: bool = false;
critical_section::with(|_| unsafe {
if _ESP_HAL_DEVICE_PERIPHERALS {
panic!("init called more than once!")
}
_ESP_HAL_DEVICE_PERIPHERALS = true;
Self::steal()
})
}
}
impl Peripherals {
/// Unsafely create an instance of this peripheral out of thin air.
///
/// # Safety
///
/// You must ensure that you're only using one instance of this type at a time.
#[inline]
pub unsafe fn steal() -> Self {
Self {
$(
$(#[$cfg])?
// $name: peripherals::$name::steal(), // FIXME add this back once we have removed pac::Peripherals completely
$name: unsafe { core::mem::zeroed() }, // this is well defined for zero sized types: https://github.com/rust-lang/unsafe-code-guidelines/issues/250
)*
}
}
}
// expose the new structs
$(
pub use peripherals::$name;
)*
}
}
#[macro_export]
macro_rules! create_peripherals {
($($(#[$cfg:meta])? $name:ident),*$(,)?) => {
$(
$(#[$cfg])?
#[derive(Debug)]
#[allow(non_camel_case_types)]
pub struct $name { _inner: () }
$(#[$cfg])?
impl $name {
/// Unsafely create an instance of this peripheral out of thin air.
///
/// # Safety
///
/// You must ensure that you're only using one instance of this type at a time.
#[inline]
pub unsafe fn steal() -> Self {
Self { _inner: () }
}
#[doc = r"Pointer to the register block"]
pub const PTR: *const <super::pac::$name as core::ops::Deref>::Target = super::pac::$name::PTR;
#[doc = r"Return the pointer to the register block"]
#[inline(always)]
pub const fn ptr() -> *const <super::pac::$name as core::ops::Deref>::Target {
super::pac::$name::PTR
}
}
impl core::ops::Deref for $name {
type Target = <super::pac::$name as core::ops::Deref>::Target;
fn deref(&self) -> &Self::Target {
unsafe { &*Self::PTR }
}
}
impl core::ops::DerefMut for $name {
fn deref_mut(&mut self) -> &mut Self::Target {
unsafe { &mut *(Self::PTR as *mut _) }
}
}
impl crate::peripheral::Peripheral for $name {
type P = $name;
#[inline]
unsafe fn clone_unchecked(&mut self) -> Self::P {
Self::steal()
}
}
impl crate::peripheral::Peripheral for &mut $name {
type P = $name;
#[inline]
unsafe fn clone_unchecked(&mut self) -> Self::P {
$name::steal()
}
}
)*
}
}
#[macro_export]
macro_rules! into_ref {
($($name:ident),*) => {
$(
let $name = $name.into_ref();
)*
}
}
}

View File

@ -0,0 +1,58 @@
pub use pac::Interrupt;
use crate::pac; // We need to export this for users to use
crate::peripherals! {
AES,
APB_CTRL,
BB,
DPORT,
EFUSE,
FLASH_ENCRYPTION,
FRC_TIMER,
GPIO,
GPIO_SD,
HINF,
I2C0,
I2C1,
I2S0,
I2S1,
IO_MUX,
LEDC,
PWM0,
PWM1,
NRX,
PCNT,
RMT,
RNG,
RSA,
RTC_CNTL,
RTCIO,
RTC_I2C,
SDMMC,
SENS,
SHA,
SLC,
SLCHOST,
SPI0,
SPI1,
SPI2,
SPI3,
TIMG0,
TIMG1,
TWAI,
UART0,
UART1,
UART2,
UHCI0,
UHCI1,
}
mod peripherals {
pub use super::pac::*;
crate::create_peripherals! {
UART0,
UART1,
}
}

View File

@ -0,0 +1,40 @@
pub use pac::Interrupt;
use crate::pac; // We need to export this for users to use
crate::peripherals! {
APB_CTRL,
APB_SARADC,
ASSIST_DEBUG,
DMA,
ECC,
EFUSE,
EXTMEM,
GPIO,
I2C0,
INTERRUPT_CORE0,
IO_MUX,
LEDC,
RNG,
RTC_CNTL,
SENSITIVE,
SHA,
SPI0,
SPI1,
SPI2,
SYSTEM,
SYSTIMER,
TIMG0,
UART0,
UART1,
XTS_AES,
}
mod peripherals {
pub use super::pac::*;
crate::create_peripherals! {
UART0,
UART1,
}
}

View File

@ -0,0 +1,51 @@
pub use pac::Interrupt;
use crate::pac; // We need to export this for users to use
crate::peripherals! {
AES,
APB_CTRL,
APB_SARADC,
ASSIST_DEBUG,
DMA,
DS,
EFUSE,
EXTMEM,
GPIO,
GPIOSD,
HMAC,
I2C0,
I2S,
INTERRUPT_CORE0,
IO_MUX,
LEDC,
RMT,
RNG,
RSA,
RTC_CNTL,
SENSITIVE,
SHA,
SPI0,
SPI1,
SPI2,
SYSTEM,
SYSTIMER,
TIMG0,
TIMG1,
TWAI,
UART0,
UART1,
UHCI0,
UHCI1,
USB_DEVICE,
XTS_AES,
}
mod peripherals {
pub use super::pac::*;
crate::create_peripherals! {
UART0,
UART1,
}
}

View File

@ -0,0 +1,56 @@
pub use pac::Interrupt;
use crate::pac; // We need to export this for users to use
crate::peripherals! {
AES,
APB_SARADC,
DEDICATED_GPIO,
DS,
EFUSE,
EXTMEM,
GPIO,
GPIO_SD,
HMAC,
I2C0,
I2C1,
I2S,
INTERRUPT,
IO_MUX,
LEDC,
PCNT,
PMS,
RMT,
RNG,
RSA,
RTCIO,
RTC_CNTL,
RTC_I2C,
SENS,
SHA,
SPI0,
SPI1,
SPI2,
SPI3,
SPI4,
SYSTEM,
SYSTIMER,
TIMG0,
TIMG1,
TWAI,
UART0,
UART1,
UHCI0,
USB0,
USB_WRAP,
XTS_AES,
}
mod peripherals {
pub use super::pac::*;
crate::create_peripherals! {
UART0,
UART1,
}
}

View File

@ -0,0 +1,67 @@
pub use pac::Interrupt;
use crate::pac; // We need to export this for users to use
crate::peripherals! {
AES,
APB_CTRL,
APB_SARADC,
DEBUG_ASSIST,
DMA,
DS,
EFUSE,
EXTMEM,
GPIO,
GPIOSD,
HMAC,
I2C0,
I2C1,
I2S0,
I2S1,
INTERRUPT_CORE0,
INTERRUPT_CORE1,
IO_MUX,
LCD_CAM,
LEDC,
PCNT,
PERI_BACKUP,
PWM0,
PWM1,
RMT,
RNG,
RSA,
RTC_CNTL,
RTC_I2C,
RTCIO,
SENS,
SENSITIVE,
SHA,
SPI0,
SPI1,
SPI2,
SPI3,
SYSTEM,
SYSTIMER,
TIMG0,
TIMG1,
TWAI,
UART0,
UART1,
UART2,
UHCI0,
UHCI1,
USB0,
USB_DEVICE,
USB_WRAP,
WCL,
XTS_AES,
}
mod peripherals {
pub use super::pac::*;
crate::create_peripherals! {
UART0,
UART1,
}
}

View File

@ -54,7 +54,6 @@ pub use crate::{
},
},
macros::*,
serial::{Instance as _esp_hal_serial_Instance, UartPins as _esp_hal_serial_UartPins},
spi::{
dma::WithDmaSpi2 as _esp_hal_spi_dma_WithDmaSpi2,
Instance as _esp_hal_spi_Instance,
@ -65,6 +64,7 @@ pub use crate::{
Instance as _esp_hal_timer_Instance,
TimerGroupInstance as _esp_hal_timer_TimerGroupInstance,
},
uart::{Instance as _esp_hal_uart_Instance, UartPins as _esp_hal_uart_UartPins},
};
/// All traits required for using the 1.0.0-alpha.x release of embedded-hal
@ -132,7 +132,6 @@ pub mod eh1 {
},
},
macros::*,
serial::{Instance as _esp_hal_serial_Instance, UartPins as _esp_hal_serial_UartPins},
spi::{
dma::WithDmaSpi2 as _esp_hal_spi_dma_WithDmaSpi2,
Instance as _esp_hal_spi_Instance,
@ -143,5 +142,6 @@ pub mod eh1 {
Instance as _esp_hal_timer_Instance,
TimerGroupInstance as _esp_hal_timer_TimerGroupInstance,
},
uart::{Instance as _esp_hal_serial_Instance, UartPins as _esp_hal_serial_UartPins},
};
}

View File

@ -36,7 +36,7 @@
//!
//! ### Example (for ESP32-C3)
//! ```
//! let mut peripherals = pac::Peripherals::take().unwrap();
//! let mut peripherals = peripherals::Peripherals::take();
//!
//! // Configure RMT peripheral globally
//! let pulse = PulseControl::new(

View File

@ -4,7 +4,7 @@
//!
//! Example
//! ```no_run
//! let peripherals = Peripherals::take().unwrap();
//! let peripherals = Peripherals::take();
//! let system = peripherals.SYSTEM.split();
//! let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
//! ```

View File

@ -86,15 +86,9 @@ impl<T, const CHANNEL: u8> Alarm<T, CHANNEL> {
pub fn interrupt_enable(&self, val: bool) {
let systimer = unsafe { &*SYSTIMER::ptr() };
match CHANNEL {
0 => systimer
.int_ena
.modify(|_, w| w.target0_int_ena().bit(val)),
1 => systimer
.int_ena
.modify(|_, w| w.target1_int_ena().bit(val)),
2 => systimer
.int_ena
.modify(|_, w| w.target2_int_ena().bit(val)),
0 => systimer.int_ena.modify(|_, w| w.target0_int_ena().bit(val)),
1 => systimer.int_ena.modify(|_, w| w.target1_int_ena().bit(val)),
2 => systimer.int_ena.modify(|_, w| w.target2_int_ena().bit(val)),
_ => unreachable!(),
}
}

View File

@ -5,11 +5,9 @@ use self::config::Config;
use crate::pac::UART2;
use crate::{
clock::Clocks,
pac::{
uart0::{fifo::FIFO_SPEC, RegisterBlock},
UART0,
UART1,
},
pac::uart0::{fifo::FIFO_SPEC, RegisterBlock},
peripheral::{Peripheral, PeripheralRef},
peripherals::{UART0, UART1},
types::{InputSignal, OutputSignal},
InputPin,
OutputPin,
@ -233,17 +231,17 @@ impl embedded_hal_1::serial::Error for Error {
}
/// UART driver
pub struct Serial<T> {
uart: T,
pub struct Uart<'d, T> {
uart: PeripheralRef<'d, T>,
}
impl<T> Serial<T>
impl<'d, T> Uart<'d, T>
where
T: Instance,
{
/// Create a new UART instance with defaults
pub fn new_with_config<P>(
uart: T,
uart: impl Peripheral<P = T> + 'd,
config: Option<Config>,
mut pins: Option<P>,
clocks: &Clocks,
@ -251,7 +249,8 @@ where
where
P: UartPins,
{
let mut serial = Serial { uart };
crate::into_ref!(uart);
let mut serial = Uart { uart };
serial.uart.disable_rx_interrupts();
serial.uart.disable_tx_interrupts();
@ -275,19 +274,15 @@ where
}
/// Create a new UART instance with defaults
pub fn new(uart: T) -> Self {
let mut serial = Serial { uart };
pub fn new(uart: impl Peripheral<P = T> + 'd) -> Self {
crate::into_ref!(uart);
let mut serial = Uart { uart };
serial.uart.disable_rx_interrupts();
serial.uart.disable_tx_interrupts();
serial
}
/// Return the raw interface to the underlying UART instance
pub fn free(self) -> T {
self.uart
}
/// Writes bytes
pub fn write_bytes(&mut self, data: &[u8]) -> Result<(), Error> {
data.iter()
@ -767,7 +762,7 @@ impl Instance for UART2 {
}
#[cfg(feature = "ufmt")]
impl<T> ufmt_write::uWrite for Serial<T>
impl<T> ufmt_write::uWrite for Uart<'_, T>
where
T: Instance,
{
@ -785,7 +780,7 @@ where
}
}
impl<T> core::fmt::Write for Serial<T>
impl<T> core::fmt::Write for Uart<'_, T>
where
T: Instance,
{
@ -795,7 +790,7 @@ where
}
}
impl<T> embedded_hal::serial::Write<u8> for Serial<T>
impl<T> embedded_hal::serial::Write<u8> for Uart<'_, T>
where
T: Instance,
{
@ -810,7 +805,7 @@ where
}
}
impl<T> embedded_hal::serial::Read<u8> for Serial<T>
impl<T> embedded_hal::serial::Read<u8> for Uart<'_, T>
where
T: Instance,
{
@ -822,12 +817,12 @@ where
}
#[cfg(feature = "eh1")]
impl<T> embedded_hal_1::serial::ErrorType for Serial<T> {
impl<T> embedded_hal_1::serial::ErrorType for Uart<'_, T> {
type Error = Error;
}
#[cfg(feature = "eh1")]
impl<T> embedded_hal_nb::serial::Read for Serial<T>
impl<T> embedded_hal_nb::serial::Read for Uart<'_, T>
where
T: Instance,
{
@ -837,7 +832,7 @@ where
}
#[cfg(feature = "eh1")]
impl<T> embedded_hal_nb::serial::Write for Serial<T>
impl<T> embedded_hal_nb::serial::Write for Uart<'_, T>
where
T: Instance,
{

View File

@ -199,7 +199,7 @@ pub fn interrupt(args: TokenStream, input: TokenStream) -> TokenStream {
f.block.stmts.extend(std::iter::once(
syn::parse2(quote! {{
// Check that this interrupt actually exists
self::pac::Interrupt::#ident_s;
crate::peripherals::Interrupt::#ident_s;
}})
.unwrap(),
));

View File

@ -9,7 +9,7 @@ use esp32_hal::{
adc::{AdcConfig, Attenuation, ADC, ADC2},
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Delay,
@ -21,7 +21,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -9,16 +9,16 @@
use esp32_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
serial::{
timer::TimerGroup,
uart::{
config::{Config, DataBits, Parity, StopBits},
TxRxPins,
},
timer::TimerGroup,
Delay,
Rtc,
Serial,
Uart,
};
use esp_backtrace as _;
use esp_println::println;
@ -27,7 +27,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -52,7 +52,7 @@ fn main() -> ! {
io.pins.gpio17.into_floating_input(),
);
let mut serial1 = Serial::new_with_config(peripherals.UART1, Some(config), Some(pins), &clocks);
let mut serial1 = Uart::new_with_config(peripherals.UART1, Some(config), Some(pins), &clocks);
let mut delay = Delay::new(&clocks);

View File

@ -8,7 +8,7 @@
use esp32_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Delay,
@ -19,7 +19,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -11,7 +11,7 @@ use critical_section::Mutex;
use esp32_hal::{
clock::ClockControl,
interrupt,
pac::{self, Peripherals},
peripherals::{self, Peripherals},
prelude::*,
Rtc,
};
@ -22,7 +22,7 @@ static RTC: Mutex<RefCell<Option<Rtc>>> = Mutex::new(RefCell::new(None));
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -40,7 +40,11 @@ fn main() -> ! {
clocks.xtal_clock.to_MHz()
);
interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap();
interrupt::enable(
peripherals::Interrupt::RTC_CORE,
interrupt::Priority::Priority1,
)
.unwrap();
critical_section::with(|cs| RTC.borrow_ref_mut(cs).replace(rtc));

View File

@ -9,7 +9,7 @@ use esp32_hal::{
clock::ClockControl,
dac,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Delay,
@ -20,7 +20,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -4,12 +4,13 @@
use embassy_executor::Executor;
use embassy_time::{Duration, Timer};
use esp32_hal::{
clock::ClockControl,
embassy,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc, embassy, pac::Peripherals,
Rtc,
};
use esp_backtrace as _;
use static_cell::StaticCell;
@ -35,7 +36,7 @@ static EXECUTOR: StaticCell<Executor> = StaticCell::new();
#[xtensa_lx_rt::entry]
fn main() -> ! {
esp_println::println!("Init!");
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -53,10 +54,9 @@ fn main() -> ! {
#[cfg(feature = "embassy-time-timg0")]
embassy::init(&clocks, timer_group0.timer0);
let executor = EXECUTOR.init(Executor::new());
executor.run(|spawner| {
spawner.spawn(run1()).ok();
spawner.spawn(run2()).ok();
});
}
}

View File

@ -11,10 +11,10 @@ use core::{borrow::BorrowMut, cell::RefCell};
use critical_section::Mutex;
use esp32_hal::{
clock::ClockControl,
gpio::{Gpio0, IO, Event, Input, PullDown,},
gpio::{Event, Gpio0, Input, PullDown, IO},
interrupt,
macros::ram,
pac::{self, Peripherals},
peripherals::{self, Peripherals},
prelude::*,
timer::TimerGroup,
Delay,
@ -27,7 +27,7 @@ static BUTTON: Mutex<RefCell<Option<Gpio0<Input<PullDown>>>>> = Mutex::new(RefCe
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -48,7 +48,7 @@ fn main() -> ! {
critical_section::with(|cs| BUTTON.borrow_ref_mut(cs).replace(button));
interrupt::enable(pac::Interrupt::GPIO, interrupt::Priority::Priority2).unwrap();
interrupt::enable(peripherals::Interrupt::GPIO, interrupt::Priority::Priority2).unwrap();
led.set_high().unwrap();

View File

@ -15,7 +15,7 @@
use esp32_hal::{
clock::ClockControl,
pac,
peripherals,
prelude::*,
timer::TimerGroup,
utils::{smartLedAdapter, SmartLedsAdapter},
@ -36,7 +36,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = pac::Peripherals::take().unwrap();
let peripherals = peripherals::Peripherals::take();
let mut system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -8,11 +8,11 @@ use core::fmt::Write;
use esp32_hal::{
clock::ClockControl,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
Serial,
Uart,
};
use esp_backtrace as _;
use nb::block;
@ -20,14 +20,14 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
let timer_group0 = TimerGroup::new(peripherals.TIMG0, &clocks);
let mut timer0 = timer_group0.timer0;
let mut wdt = timer_group0.wdt;
let mut serial0 = Serial::new(peripherals.UART0);
let mut serial0 = Uart::new(peripherals.UART0);
let mut rtc = Rtc::new(peripherals.RTC_CNTL);
// Disable MWDT and RWDT (Watchdog) flash boot protection

View File

@ -13,7 +13,7 @@ use esp32_hal::{
clock::ClockControl,
gpio::IO,
i2c::I2C,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -24,7 +24,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -23,7 +23,7 @@ use esp32_hal::{
clock::ClockControl,
gpio::IO,
i2c::I2C,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -35,7 +35,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -1,5 +1,5 @@
//! This shows how to continously receive data via I2S
//!
//!
//! Pins used
//! BCLK GPIO12
//! WS GPIO13
@ -7,7 +7,7 @@
//!
//! Without an additional I2S source device you can connect 3V3 or GND to DIN to
//! read 0 or 0xFF or connect DIN to WS to read two different values
//!
//!
//! You can also inspect the MCLK, BCLK and WS with a logic analyzer
#![no_std]
@ -15,10 +15,10 @@
use esp32_hal::{
clock::ClockControl,
dma::{DmaPriority},
dma::DmaPriority,
i2s::{DataFormat, I2s, I2s0New, I2sReadDma, NoMclk, PinsBclkWsDin, Standard},
pdma::Dma,
i2s::{DataFormat, I2s, NoMclk, Standard, I2s0New, PinsBclkWsDin, I2sReadDma},
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -30,7 +30,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -32,9 +32,9 @@
use esp32_hal::{
clock::ClockControl,
dma::DmaPriority,
i2s::{DataFormat, I2s, I2s0New, I2sWriteDma, NoMclk, PinsBclkWsDout, Standard},
pdma::Dma,
i2s::{DataFormat, I2s, I2sWriteDma, NoMclk, PinsBclkWsDout, Standard, I2s0New},
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -53,7 +53,7 @@ const SINE: [i16; 64] = [
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -15,7 +15,7 @@ use esp32_hal::{
HighSpeed,
LEDC,
},
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -25,7 +25,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -1,4 +1,5 @@
//! Uses timer0 and operator0 of the MCPWM0 peripheral to output a 50% duty signal at 20 kHz.
//! Uses timer0 and operator0 of the MCPWM0 peripheral to output a 50% duty
//! signal at 20 kHz.
//!
//! The signal will be output to the pin assigned to `pin`. (GPIO4)
@ -8,12 +9,8 @@
use esp32_hal::{
clock::ClockControl,
gpio::IO,
mcpwm::{
{MCPWM, PeripheralClockConfig},
operator::PwmPinConfig,
timer::PwmWorkingMode,
},
pac::Peripherals,
mcpwm::{operator::PwmPinConfig, timer::PwmWorkingMode, PeripheralClockConfig, MCPWM},
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -23,7 +20,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -53,8 +50,11 @@ fn main() -> ! {
.operator0
.with_pin_a(pin, PwmPinConfig::UP_ACTIVE_HIGH);
// start timer with timestamp values in the range of 0..=99 and a frequency of 20 kHz
let timer_clock_cfg = clock_cfg.timer_clock_with_frequency(99, PwmWorkingMode::Increase, 20u32.kHz()).unwrap();
// 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, 20u32.kHz())
.unwrap();
mcpwm.timer0.start(timer_clock_cfg);
// pin will be high 50% of the time

View File

@ -10,7 +10,7 @@ use core::cell::RefCell;
use critical_section::Mutex;
use esp32_hal::{
clock::ClockControl,
pac::{Peripherals, TIMG1},
peripherals::{Peripherals, TIMG1},
prelude::*,
timer::{Timer, Timer0, TimerGroup},
CpuControl,
@ -23,7 +23,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -8,7 +8,7 @@
use esp32_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
pulse_control::{ConfiguredChannel, OutputChannel, PulseCode, RepeatMode},
timer::TimerGroup,
@ -20,7 +20,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -11,7 +11,7 @@
use esp32_hal::{
clock::ClockControl,
macros::ram,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
};
@ -31,7 +31,7 @@ static mut SOME_ZEROED_DATA: [u8; 8] = [0; 8];
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -7,7 +7,7 @@
use esp32_hal::{
clock::ClockControl,
efuse::Efuse,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -18,7 +18,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -12,7 +12,7 @@ use critical_section::Mutex;
use esp32_hal::{
clock::ClockControl,
interrupt,
pac::{self, Peripherals},
peripherals::{self, Peripherals},
prelude::*,
Rtc,
Rwdt,
@ -24,7 +24,7 @@ static RWDT: Mutex<RefCell<Option<Rwdt>>> = Mutex::new(RefCell::new(None));
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let _clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -38,7 +38,11 @@ fn main() -> ! {
critical_section::with(|cs| RWDT.borrow_ref_mut(cs).replace(rtc.rwdt));
interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap();
interrupt::enable(
peripherals::Interrupt::RTC_CORE,
interrupt::Priority::Priority1,
)
.unwrap();
loop {}
}

View File

@ -11,22 +11,22 @@ use critical_section::Mutex;
use esp32_hal::{
clock::ClockControl,
interrupt,
pac::{self, Peripherals, UART0},
peripherals::{self, Peripherals, UART0},
prelude::*,
serial::config::AtCmdConfig,
timer::TimerGroup,
uart::config::AtCmdConfig,
Rtc,
Serial,
Uart,
};
use esp_backtrace as _;
use nb::block;
use xtensa_lx_rt::entry;
static SERIAL: Mutex<RefCell<Option<Serial<UART0>>>> = Mutex::new(RefCell::new(None));
static SERIAL: Mutex<RefCell<Option<Uart<UART0>>>> = Mutex::new(RefCell::new(None));
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -38,7 +38,7 @@ fn main() -> ! {
let timer_group1 = TimerGroup::new(peripherals.TIMG1, &clocks);
let mut wdt1 = timer_group1.wdt;
let mut serial0 = Serial::new(peripherals.UART0);
let mut serial0 = Uart::new(peripherals.UART0);
let mut rtc = Rtc::new(peripherals.RTC_CNTL);
// Disable MWDT and RWDT (Watchdog) flash boot protection
@ -51,7 +51,11 @@ fn main() -> ! {
serial0.listen_at_cmd();
serial0.listen_rx_fifo_full();
interrupt::enable(pac::Interrupt::UART0, interrupt::Priority::Priority2).unwrap();
interrupt::enable(
peripherals::Interrupt::UART0,
interrupt::Priority::Priority2,
)
.unwrap();
timer0.start(1u64.secs());

View File

@ -1,26 +1,26 @@
//! Demonstrates the use of the SHA peripheral and compares the speed of hardware-accelerated and pure software hashing.
//!
//! Demonstrates the use of the SHA peripheral and compares the speed of
//! hardware-accelerated and pure software hashing.
#![no_std]
#![no_main]
use esp32_hal::{
clock::ClockControl,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
sha::{Sha, ShaMode},
timer::TimerGroup,
Rtc,
sha::{Sha, ShaMode},
};
use nb::block;
use esp_backtrace as _;
use esp_println::println;
use nb::block;
use sha2::{Digest, Sha512};
use xtensa_lx_rt::entry;
use sha2::{Sha512, Digest};
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -32,30 +32,34 @@ fn main() -> ! {
wdt.disable();
rtc.rwdt.disable();
let source_data = "aaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaa".as_bytes();
let mut remaining = source_data.clone();
let mut hasher = Sha::new(peripherals.SHA, ShaMode::SHA512);
// Short hashes can be created by decreasing the output buffer to the desired length
// Short hashes can be created by decreasing the output buffer to the desired
// length
let mut output = [0u8; 64];
let pre_calc = xtensa_lx::timer::get_cycle_count();
// The hardware implementation takes a subslice of the input, and returns the unprocessed parts
// The unprocessed parts can be input in the next iteration, you can always add more data until
// finish() is called. After finish() is called update()'s will contribute to a new hash which
// The hardware implementation takes a subslice of the input, and returns the
// unprocessed parts The unprocessed parts can be input in the next
// iteration, you can always add more data until finish() is called. After
// finish() is called update()'s will contribute to a new hash which
// can be extracted again with finish().
while remaining.len() > 0 {
// Can add println to view progress, however println takes a few orders of magnitude longer than
// the Sha function itself so not useful for comparing processing time
// println!("Remaining len: {}", remaining.len());
// All the HW Sha functions are infallible so unwrap is fine to use if you use block!
while remaining.len() > 0 {
// Can add println to view progress, however println takes a few orders of
// magnitude longer than the Sha function itself so not useful for
// comparing processing time println!("Remaining len: {}",
// remaining.len());
// All the HW Sha functions are infallible so unwrap is fine to use if you use
// block!
remaining = block!(hasher.update(remaining)).unwrap();
}
// Finish can be called as many times as desired to get mutliple copies of the output.
// Finish can be called as many times as desired to get mutliple copies of the
// output.
block!(hasher.finish(output.as_mut_slice())).unwrap();
let post_calc = xtensa_lx::timer::get_cycle_count();
@ -64,7 +68,6 @@ fn main() -> ! {
println!("SHA512 Hash output {:02x?}", output);
let _usha = hasher.free();
let pre_calc = xtensa_lx::timer::get_cycle_count();
let mut hasher = Sha512::new();
hasher.update(source_data);
@ -74,7 +77,7 @@ fn main() -> ! {
println!("Took {} cycles", soft_time);
println!("SHA512 Hash output {:02x?}", soft_result);
println!("HW SHA is {}x faster", soft_time/hw_time);
println!("HW SHA is {}x faster", soft_time / hw_time);
loop {}
}

View File

@ -22,7 +22,7 @@ use embedded_hal_1::spi::SpiDevice;
use esp32_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
spi::{Spi, SpiBusController, SpiMode},
timer::TimerGroup,
@ -35,7 +35,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -20,7 +20,7 @@ use embedded_hal_1::spi::SpiBus;
use esp32_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
spi::{Spi, SpiMode},
timer::TimerGroup,
@ -33,7 +33,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -19,7 +19,7 @@
use esp32_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
spi::{Spi, SpiMode},
timer::TimerGroup,
@ -32,7 +32,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -18,10 +18,10 @@
use esp32_hal::{
clock::ClockControl,
dma::{DmaPriority},
dma::DmaPriority,
gpio::IO,
pac::Peripherals,
pdma::Dma,
peripherals::Peripherals,
prelude::*,
spi::{Spi, SpiMode},
timer::TimerGroup,
@ -34,7 +34,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -12,7 +12,7 @@ use esp32_hal::{
clock::ClockControl,
interrupt,
interrupt::Priority,
pac::{self, Peripherals, TIMG0, TIMG1},
peripherals::{self, Peripherals, TIMG0, TIMG1},
prelude::*,
timer::{Timer, Timer0, Timer1, TimerGroup},
Rtc,
@ -27,7 +27,7 @@ static TIMER11: Mutex<RefCell<Option<Timer<Timer1<TIMG1>>>>> = Mutex::new(RefCel
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -49,10 +49,10 @@ fn main() -> ! {
wdt1.disable();
rtc.rwdt.disable();
interrupt::enable(pac::Interrupt::TG0_T0_LEVEL, Priority::Priority2).unwrap();
interrupt::enable(pac::Interrupt::TG0_T1_LEVEL, Priority::Priority2).unwrap();
interrupt::enable(pac::Interrupt::TG1_T0_LEVEL, Priority::Priority3).unwrap();
interrupt::enable(pac::Interrupt::TG1_T1_LEVEL, Priority::Priority3).unwrap();
interrupt::enable(peripherals::Interrupt::TG0_T0_LEVEL, Priority::Priority2).unwrap();
interrupt::enable(peripherals::Interrupt::TG0_T1_LEVEL, Priority::Priority2).unwrap();
interrupt::enable(peripherals::Interrupt::TG1_T0_LEVEL, Priority::Priority3).unwrap();
interrupt::enable(peripherals::Interrupt::TG1_T1_LEVEL, Priority::Priority3).unwrap();
timer00.start(500u64.millis());
timer00.listen();
timer01.start(2500u64.millis());

View File

@ -5,7 +5,13 @@
#![no_std]
#![no_main]
use esp32_hal::{clock::ClockControl, pac::Peripherals, prelude::*, timer::TimerGroup, Rtc};
use esp32_hal::{
clock::ClockControl,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
};
use esp_backtrace as _;
use esp_println::println;
use nb::block;
@ -13,7 +19,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.DPORT.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -1,6 +1,8 @@
#![no_std]
pub use embedded_hal as ehal;
#[cfg(feature = "embassy")]
pub use esp_hal_common::embassy;
#[doc(inline)]
pub use esp_hal_common::{
analog::adc::implementation as adc,
@ -17,13 +19,14 @@ pub use esp_hal_common::{
ledc,
macros,
mcpwm,
pac,
peripherals,
prelude,
pulse_control,
serial,
sha,
spi,
system,
timer,
uart,
utils,
Cpu,
Delay,
@ -31,22 +34,18 @@ pub use esp_hal_common::{
Rng,
Rtc,
Rwdt,
Serial,
sha
Uart,
};
pub use self::gpio::IO;
#[cfg(feature = "embassy")]
pub use esp_hal_common::embassy;
/// Common module for analog functions
pub mod analog {
pub use esp_hal_common::analog::{AvailableAnalog, SensExt};
}
#[no_mangle]
extern "C" fn EspDefaultHandler(_level: u32, _interrupt: pac::Interrupt) {}
extern "C" fn EspDefaultHandler(_level: u32, _interrupt: peripherals::Interrupt) {}
#[no_mangle]
extern "C" fn DefaultHandler() {}

View File

@ -9,7 +9,7 @@ use esp32c2_hal::{
adc::{AdcConfig, Attenuation, ADC, ADC1},
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Delay,
@ -21,7 +21,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -8,15 +8,15 @@
use esp32c2_hal::{
clock::ClockControl,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
serial::{
timer::TimerGroup,
uart::{
config::{Config, DataBits, Parity, StopBits},
TxRxPins,
},
timer::TimerGroup,
Rtc,
Serial,
Uart,
IO,
};
use esp_backtrace as _;
@ -26,7 +26,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -53,7 +53,7 @@ fn main() -> ! {
io.pins.gpio2.into_floating_input(),
);
let mut serial1 = Serial::new_with_config(peripherals.UART1, Some(config), Some(pins), &clocks);
let mut serial1 = Uart::new_with_config(peripherals.UART1, Some(config), Some(pins), &clocks);
timer0.start(250u64.millis());

View File

@ -8,7 +8,7 @@
use esp32c2_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Delay,
@ -19,7 +19,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -11,7 +11,7 @@ use critical_section::Mutex;
use esp32c2_hal::{
clock::ClockControl,
interrupt,
pac::{self, Peripherals},
peripherals::{self, Peripherals},
prelude::*,
Rtc,
};
@ -22,7 +22,7 @@ static RTC: Mutex<RefCell<Option<Rtc>>> = Mutex::new(RefCell::new(None));
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -41,7 +41,11 @@ fn main() -> ! {
clocks.xtal_clock.to_MHz()
);
interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap();
interrupt::enable(
peripherals::Interrupt::RTC_CORE,
interrupt::Priority::Priority1,
)
.unwrap();
critical_section::with(|cs| {
RTC.borrow_ref_mut(cs).replace(rtc);

View File

@ -7,7 +7,7 @@ use embassy_time::{Duration, Timer};
use esp32c2_hal::{
clock::ClockControl,
embassy,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -36,7 +36,7 @@ static EXECUTOR: StaticCell<Executor> = StaticCell::new();
#[riscv_rt::entry]
fn main() -> ! {
esp_println::println!("Init!");
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -50,7 +50,10 @@ fn main() -> ! {
wdt0.disable();
#[cfg(feature = "embassy-time-systick")]
embassy::init(&clocks, esp32c2_hal::systimer::SystemTimer::new(peripherals.SYSTIMER));
embassy::init(
&clocks,
esp32c2_hal::systimer::SystemTimer::new(peripherals.SYSTIMER),
);
#[cfg(feature = "embassy-time-timg0")]
embassy::init(&clocks, timer_group0.timer0);

View File

@ -11,9 +11,9 @@ use core::cell::RefCell;
use critical_section::Mutex;
use esp32c2_hal::{
clock::ClockControl,
gpio::{Gpio9, IO, Event, Input, PullDown},
gpio::{Event, Gpio9, Input, PullDown, IO},
interrupt,
pac::{self, Peripherals},
peripherals::{self, Peripherals},
prelude::*,
timer::TimerGroup,
Delay,
@ -26,7 +26,7 @@ static BUTTON: Mutex<RefCell<Option<Gpio9<Input<PullDown>>>>> = Mutex::new(RefCe
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -50,7 +50,7 @@ fn main() -> ! {
critical_section::with(|cs| BUTTON.borrow_ref_mut(cs).replace(button));
interrupt::enable(pac::Interrupt::GPIO, interrupt::Priority::Priority3).unwrap();
interrupt::enable(peripherals::Interrupt::GPIO, interrupt::Priority::Priority3).unwrap();
unsafe {
riscv::interrupt::enable();

View File

@ -8,11 +8,11 @@ use core::fmt::Write;
use esp32c2_hal::{
clock::ClockControl,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
Serial,
Uart,
};
use esp_backtrace as _;
use nb::block;
@ -20,12 +20,12 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
let mut rtc = Rtc::new(peripherals.RTC_CNTL);
let mut serial0 = Serial::new(peripherals.UART0);
let mut serial0 = Uart::new(peripherals.UART0);
let timer_group0 = TimerGroup::new(peripherals.TIMG0, &clocks);
let mut timer0 = timer_group0.timer0;
let mut wdt0 = timer_group0.wdt;

View File

@ -13,7 +13,7 @@ use esp32c2_hal::{
clock::ClockControl,
gpio::IO,
i2c::I2C,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -24,7 +24,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -23,7 +23,7 @@ use esp32c2_hal::{
clock::ClockControl,
gpio::IO,
i2c::I2C,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -35,7 +35,7 @@ use ssd1306::{prelude::*, I2CDisplayInterface, Ssd1306};
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -16,7 +16,7 @@ use esp32c2_hal::{
LowSpeed,
LEDC,
},
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -26,7 +26,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -7,7 +7,7 @@
use esp32c2_hal::{
clock::ClockControl,
efuse::Efuse,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -18,7 +18,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -12,7 +12,7 @@ use critical_section::Mutex;
use esp32c2_hal::{
clock::ClockControl,
interrupt,
pac::{self, Peripherals},
peripherals::{self, Peripherals},
prelude::*,
Rtc,
Rwdt,
@ -24,7 +24,7 @@ static RWDT: Mutex<RefCell<Option<Rwdt>>> = Mutex::new(RefCell::new(None));
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let _clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -37,7 +37,11 @@ fn main() -> ! {
rtc.rwdt.start(2000u64.millis());
rtc.rwdt.listen();
interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap();
interrupt::enable(
peripherals::Interrupt::RTC_CORE,
interrupt::Priority::Priority1,
)
.unwrap();
critical_section::with(|cs| RWDT.borrow_ref_mut(cs).replace(rtc.rwdt));

View File

@ -11,28 +11,28 @@ use critical_section::Mutex;
use esp32c2_hal::{
clock::ClockControl,
interrupt,
pac::{self, Peripherals, UART0},
peripherals::{self, Peripherals, UART0},
prelude::*,
serial::config::AtCmdConfig,
timer::TimerGroup,
uart::config::AtCmdConfig,
Cpu,
Rtc,
Serial,
Uart,
};
use esp_backtrace as _;
use nb::block;
use riscv_rt::entry;
static SERIAL: Mutex<RefCell<Option<Serial<UART0>>>> = Mutex::new(RefCell::new(None));
static SERIAL: Mutex<RefCell<Option<Uart<UART0>>>> = Mutex::new(RefCell::new(None));
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
let mut rtc = Rtc::new(peripherals.RTC_CNTL);
let mut serial0 = Serial::new(peripherals.UART0);
let mut serial0 = Uart::new(peripherals.UART0);
let timer_group0 = TimerGroup::new(peripherals.TIMG0, &clocks);
let mut timer0 = timer_group0.timer0;
let mut wdt0 = timer_group0.wdt;
@ -51,7 +51,11 @@ fn main() -> ! {
critical_section::with(|cs| SERIAL.borrow_ref_mut(cs).replace(serial0));
interrupt::enable(pac::Interrupt::UART0, interrupt::Priority::Priority1).unwrap();
interrupt::enable(
peripherals::Interrupt::UART0,
interrupt::Priority::Priority1,
)
.unwrap();
interrupt::set_kind(
Cpu::ProCpu,
interrupt::CpuInterrupt::Interrupt1, // Interrupt 1 handles priority one interrupts

View File

@ -1,26 +1,26 @@
//! Demonstrates the use of the SHA peripheral and compares the speed of hardware-accelerated and pure software hashing.
//!
//! Demonstrates the use of the SHA peripheral and compares the speed of
//! hardware-accelerated and pure software hashing.
#![no_std]
#![no_main]
use esp32c2_hal::{
clock::ClockControl,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
sha::{Sha, ShaMode},
timer::TimerGroup,
Rtc,
sha::{Sha, ShaMode},
};
use nb::block;
use esp_backtrace as _;
use esp_println::println;
use nb::block;
use riscv_rt::entry;
use sha2::{Sha256, Digest};
use sha2::{Digest, Sha256};
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -32,48 +32,51 @@ fn main() -> ! {
wdt.disable();
rtc.rwdt.disable();
let source_data = "aaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaa".as_bytes();
let mut remaining = source_data.clone();
let mut hasher = Sha::new(peripherals.SHA, ShaMode::SHA256);
// Short hashes can be created by decreasing the output buffer to the desired length
// Short hashes can be created by decreasing the output buffer to the desired
// length
let mut output = [0u8; 32];
//let pre_calc = xtensa_lx::timer::get_cycle_count();
// The hardware implementation takes a subslice of the input, and returns the unprocessed parts
// The unprocessed parts can be input in the next iteration, you can always add more data until
// finish() is called. After finish() is called update()'s will contribute to a new hash which
// let pre_calc = xtensa_lx::timer::get_cycle_count();
// The hardware implementation takes a subslice of the input, and returns the
// unprocessed parts The unprocessed parts can be input in the next
// iteration, you can always add more data until finish() is called. After
// finish() is called update()'s will contribute to a new hash which
// can be extracted again with finish().
while remaining.len() > 0 {
// Can add println to view progress, however println takes a few orders of magnitude longer than
// the Sha function itself so not useful for comparing processing time
// println!("Remaining len: {}", remaining.len());
// All the HW Sha functions are infallible so unwrap is fine to use if you use block!
while remaining.len() > 0 {
// Can add println to view progress, however println takes a few orders of
// magnitude longer than the Sha function itself so not useful for
// comparing processing time println!("Remaining len: {}",
// remaining.len());
// All the HW Sha functions are infallible so unwrap is fine to use if you use
// block!
remaining = block!(hasher.update(remaining)).unwrap();
}
// Finish can be called as many times as desired to get mutliple copies of the output.
// Finish can be called as many times as desired to get mutliple copies of the
// output.
block!(hasher.finish(output.as_mut_slice())).unwrap();
//let post_calc = xtensa_lx::timer::get_cycle_count();
//let hw_time = post_calc - pre_calc;
//println!("Took {} cycles", hw_time);
// let post_calc = xtensa_lx::timer::get_cycle_count();
// let hw_time = post_calc - pre_calc;
// println!("Took {} cycles", hw_time);
println!("SHA256 Hash output {:02x?}", output);
let _usha = hasher.free();
//let pre_calc = xtensa_lx::timer::get_cycle_count();
// let pre_calc = xtensa_lx::timer::get_cycle_count();
let mut hasher = Sha256::new();
hasher.update(source_data);
let soft_result = hasher.finalize();
//let post_calc = xtensa_lx::timer::get_cycle_count();
//let soft_time = post_calc - pre_calc;
//println!("Took {} cycles", soft_time);
// let post_calc = xtensa_lx::timer::get_cycle_count();
// let soft_time = post_calc - pre_calc;
// println!("Took {} cycles", soft_time);
println!("SHA256 Hash output {:02x?}", soft_result);
//println!("HW SHA is {}x faster", soft_time/hw_time);
// println!("HW SHA is {}x faster", soft_time/hw_time);
loop {}
}

View File

@ -22,7 +22,7 @@ use embedded_hal_1::spi::SpiDevice;
use esp32c2_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
spi::{Spi, SpiBusController, SpiMode},
timer::TimerGroup,
@ -35,7 +35,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -20,7 +20,7 @@ use embedded_hal_1::spi::SpiBus;
use esp32c2_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
spi::{Spi, SpiMode},
timer::TimerGroup,
@ -33,7 +33,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -19,7 +19,7 @@
use esp32c2_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
spi::{Spi, SpiMode},
timer::TimerGroup,
@ -32,7 +32,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -18,10 +18,10 @@
use esp32c2_hal::{
clock::ClockControl,
dma::{DmaPriority},
dma::DmaPriority,
gdma::Gdma,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
spi::{Spi, SpiMode},
timer::TimerGroup,
@ -34,7 +34,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -11,7 +11,7 @@ use esp32c2_hal::{
clock::ClockControl,
interrupt,
interrupt::Priority,
pac::{self, Peripherals},
peripherals::{self, Peripherals},
prelude::*,
systimer::{Alarm, Periodic, SystemTimer, Target},
timer::TimerGroup,
@ -28,7 +28,7 @@ static ALARM2: Mutex<RefCell<Option<Alarm<Target, 2>>>> = Mutex::new(RefCell::ne
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -63,9 +63,21 @@ fn main() -> ! {
ALARM2.borrow_ref_mut(cs).replace(alarm2);
});
interrupt::enable(pac::Interrupt::SYSTIMER_TARGET0, Priority::Priority1).unwrap();
interrupt::enable(pac::Interrupt::SYSTIMER_TARGET1, Priority::Priority2).unwrap();
interrupt::enable(pac::Interrupt::SYSTIMER_TARGET2, Priority::Priority2).unwrap();
interrupt::enable(
peripherals::Interrupt::SYSTIMER_TARGET0,
Priority::Priority1,
)
.unwrap();
interrupt::enable(
peripherals::Interrupt::SYSTIMER_TARGET1,
Priority::Priority2,
)
.unwrap();
interrupt::enable(
peripherals::Interrupt::SYSTIMER_TARGET2,
Priority::Priority2,
)
.unwrap();
// Initialize the Delay peripheral, and use it to toggle the LED state in a
// loop.

View File

@ -10,7 +10,7 @@ use critical_section::Mutex;
use esp32c2_hal::{
clock::ClockControl,
interrupt,
pac::{self, Peripherals, TIMG0},
peripherals::{self, Peripherals, TIMG0},
prelude::*,
timer::{Timer, Timer0, TimerGroup},
Rtc,
@ -22,7 +22,7 @@ static TIMER0: Mutex<RefCell<Option<Timer<Timer0<TIMG0>>>>> = Mutex::new(RefCell
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -37,7 +37,11 @@ fn main() -> ! {
rtc.rwdt.disable();
wdt0.disable();
interrupt::enable(pac::Interrupt::TG0_T0_LEVEL, interrupt::Priority::Priority1).unwrap();
interrupt::enable(
peripherals::Interrupt::TG0_T0_LEVEL,
interrupt::Priority::Priority1,
)
.unwrap();
timer0.start(500u64.millis());
timer0.listen();

View File

@ -5,7 +5,13 @@
#![no_std]
#![no_main]
use esp32c2_hal::{clock::ClockControl, pac::Peripherals, prelude::*, timer::TimerGroup, Rtc};
use esp32c2_hal::{
clock::ClockControl,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
};
use esp_backtrace as _;
use esp_println::println;
use nb::block;
@ -13,7 +19,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -16,20 +16,20 @@ pub use esp_hal_common::{
interrupt,
ledc,
macros,
pac,
peripherals,
prelude,
serial,
sha,
spi,
system,
systimer,
timer,
uart,
Cpu,
Delay,
Rng,
Rtc,
Rwdt,
Serial,
sha,
Uart,
};
pub use self::gpio::IO;
@ -295,4 +295,4 @@ pub fn mp_hook() -> bool {
}
#[no_mangle]
extern "C" fn EspDefaultHandler(_interrupt: pac::Interrupt) {}
extern "C" fn EspDefaultHandler(_interrupt: peripherals::Interrupt) {}

View File

@ -9,7 +9,7 @@ use esp32c3_hal::{
adc::{AdcConfig, Attenuation, ADC, ADC1},
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Delay,
@ -21,7 +21,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -8,15 +8,15 @@
use esp32c3_hal::{
clock::ClockControl,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
serial::{
timer::TimerGroup,
uart::{
config::{Config, DataBits, Parity, StopBits},
TxRxPins,
},
timer::TimerGroup,
Rtc,
Serial,
Uart,
IO,
};
use esp_backtrace as _;
@ -26,7 +26,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -56,7 +56,7 @@ fn main() -> ! {
io.pins.gpio2.into_floating_input(),
);
let mut serial1 = Serial::new_with_config(peripherals.UART1, Some(config), Some(pins), &clocks);
let mut serial1 = Uart::new_with_config(peripherals.UART1, Some(config), Some(pins), &clocks);
timer0.start(250u64.millis());

View File

@ -8,7 +8,7 @@
use esp32c3_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Delay,
@ -19,7 +19,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -11,7 +11,7 @@ use critical_section::Mutex;
use esp32c3_hal::{
clock::ClockControl,
interrupt,
pac::{self, Peripherals},
peripherals::{self, Peripherals},
prelude::*,
Rtc,
};
@ -22,7 +22,7 @@ static RTC: Mutex<RefCell<Option<Rtc>>> = Mutex::new(RefCell::new(None));
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -41,7 +41,11 @@ fn main() -> ! {
clocks.xtal_clock.to_MHz()
);
interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap();
interrupt::enable(
peripherals::Interrupt::RTC_CORE,
interrupt::Priority::Priority1,
)
.unwrap();
critical_section::with(|cs| {
RTC.borrow_ref_mut(cs).replace(rtc);

View File

@ -4,12 +4,13 @@
use embassy_executor::Executor;
use embassy_time::{Duration, Timer};
use esp32c3_hal::{
clock::ClockControl,
embassy,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc, embassy, pac::Peripherals,
Rtc,
};
use esp_backtrace as _;
use static_cell::StaticCell;
@ -35,7 +36,7 @@ static EXECUTOR: StaticCell<Executor> = StaticCell::new();
#[riscv_rt::entry]
fn main() -> ! {
esp_println::println!("Init!");
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -52,7 +53,10 @@ fn main() -> ! {
wdt1.disable();
#[cfg(feature = "embassy-time-systick")]
embassy::init(&clocks, esp32c3_hal::systimer::SystemTimer::new(peripherals.SYSTIMER));
embassy::init(
&clocks,
esp32c3_hal::systimer::SystemTimer::new(peripherals.SYSTIMER),
);
#[cfg(feature = "embassy-time-timg0")]
embassy::init(&clocks, timer_group0.timer0);
@ -62,4 +66,4 @@ fn main() -> ! {
spawner.spawn(run1()).ok();
spawner.spawn(run2()).ok();
});
}
}

View File

@ -11,9 +11,9 @@ use core::cell::RefCell;
use critical_section::Mutex;
use esp32c3_hal::{
clock::ClockControl,
gpio::{Gpio9, IO, Event, Input, PullDown},
gpio::{Event, Gpio9, Input, PullDown, IO},
interrupt,
pac::{self, Peripherals},
peripherals::{self, Peripherals},
prelude::*,
timer::TimerGroup,
Delay,
@ -26,7 +26,7 @@ static BUTTON: Mutex<RefCell<Option<Gpio9<Input<PullDown>>>>> = Mutex::new(RefCe
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -53,7 +53,7 @@ fn main() -> ! {
critical_section::with(|cs| BUTTON.borrow_ref_mut(cs).replace(button));
interrupt::enable(pac::Interrupt::GPIO, interrupt::Priority::Priority3).unwrap();
interrupt::enable(peripherals::Interrupt::GPIO, interrupt::Priority::Priority3).unwrap();
unsafe {
riscv::interrupt::enable();

View File

@ -13,7 +13,7 @@
use esp32c3_hal::{
clock::ClockControl,
pac,
peripherals,
prelude::*,
pulse_control::ClockSource,
timer::TimerGroup,
@ -35,7 +35,7 @@ use smart_leds::{
#[entry]
fn main() -> ! {
let peripherals = pac::Peripherals::take().unwrap();
let peripherals = peripherals::Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -1,4 +1,4 @@
//! This shows how to write text to serial0.
//! This shows how to write text to uart0.
//! You can see the output with `espflash` if you provide the `--monitor` option
#![no_std]
@ -8,11 +8,11 @@ use core::fmt::Write;
use esp32c3_hal::{
clock::ClockControl,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
Serial,
Uart,
};
use esp_backtrace as _;
use nb::block;
@ -20,12 +20,12 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
let mut rtc = Rtc::new(peripherals.RTC_CNTL);
let mut serial0 = Serial::new(peripherals.UART0);
let mut uart0 = Uart::new(peripherals.UART0);
let timer_group0 = TimerGroup::new(peripherals.TIMG0, &clocks);
let mut timer0 = timer_group0.timer0;
let mut wdt0 = timer_group0.wdt;
@ -41,7 +41,7 @@ fn main() -> ! {
timer0.start(1u64.secs());
loop {
writeln!(serial0, "Hello world!").unwrap();
writeln!(uart0, "Hello world!").unwrap();
block!(timer0.wait()).unwrap();
}
}

View File

@ -13,7 +13,7 @@ use esp32c3_hal::{
clock::ClockControl,
gpio::IO,
i2c::I2C,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -24,7 +24,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -23,7 +23,7 @@ use esp32c3_hal::{
clock::ClockControl,
gpio::IO,
i2c::I2C,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -35,7 +35,7 @@ use ssd1306::{prelude::*, I2CDisplayInterface, Ssd1306};
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -1,5 +1,5 @@
//! This shows how to continously receive data via I2S
//!
//!
//! Pins used
//! MCLK GPIO4
//! BCLK GPIO1
@ -8,7 +8,7 @@
//!
//! Without an additional I2S source device you can connect 3V3 or GND to DIN to
//! read 0 or 0xFF or connect DIN to WS to read two different values
//!
//!
//! You can also inspect the MCLK, BCLK and WS with a logic analyzer
#![no_std]
@ -18,8 +18,8 @@ use esp32c3_hal::{
clock::ClockControl,
dma::DmaPriority,
gdma::Gdma,
i2s::{DataFormat, I2s, I2sReadDma, MclkPin, PinsBclkWsDin, Standard, I2s0New},
pac::Peripherals,
i2s::{DataFormat, I2s, I2s0New, I2sReadDma, MclkPin, PinsBclkWsDin, Standard},
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -31,7 +31,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -34,8 +34,8 @@ use esp32c3_hal::{
clock::ClockControl,
dma::DmaPriority,
gdma::Gdma,
i2s::{DataFormat, I2s, I2sWriteDma, MclkPin, PinsBclkWsDout, Standard, I2s0New},
pac::Peripherals,
i2s::{DataFormat, I2s, I2s0New, I2sWriteDma, MclkPin, PinsBclkWsDout, Standard},
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -54,7 +54,7 @@ const SINE: [i16; 64] = [
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -16,7 +16,7 @@ use esp32c3_hal::{
LowSpeed,
LEDC,
},
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -26,7 +26,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -8,7 +8,7 @@
use esp32c3_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
pulse_control::{ClockSource, ConfiguredChannel, OutputChannel, PulseCode, RepeatMode},
timer::TimerGroup,
@ -20,7 +20,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -11,7 +11,7 @@
use esp32c3_hal::{
clock::ClockControl,
macros::ram,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
};
@ -31,7 +31,7 @@ static mut SOME_ZEROED_DATA: [u8; 8] = [0; 8];
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -7,7 +7,7 @@
use esp32c3_hal::{
clock::ClockControl,
efuse::Efuse,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
@ -18,7 +18,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -12,7 +12,7 @@ use critical_section::Mutex;
use esp32c3_hal::{
clock::ClockControl,
interrupt,
pac::{self, Peripherals},
peripherals::{self, Peripherals},
prelude::*,
Rtc,
Rwdt,
@ -24,7 +24,7 @@ static RWDT: Mutex<RefCell<Option<Rwdt>>> = Mutex::new(RefCell::new(None));
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let _clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -37,7 +37,11 @@ fn main() -> ! {
rtc.rwdt.start(2000u64.millis());
rtc.rwdt.listen();
interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap();
interrupt::enable(
peripherals::Interrupt::RTC_CORE,
interrupt::Priority::Priority1,
)
.unwrap();
critical_section::with(|cs| RWDT.borrow_ref_mut(cs).replace(rtc.rwdt));

View File

@ -11,28 +11,28 @@ use critical_section::Mutex;
use esp32c3_hal::{
clock::ClockControl,
interrupt,
pac::{self, Peripherals, UART0},
peripherals::{self, Peripherals, UART0},
prelude::*,
serial::config::AtCmdConfig,
timer::TimerGroup,
uart::config::AtCmdConfig,
Cpu,
Rtc,
Serial,
Uart,
};
use esp_backtrace as _;
use nb::block;
use riscv_rt::entry;
static SERIAL: Mutex<RefCell<Option<Serial<UART0>>>> = Mutex::new(RefCell::new(None));
static SERIAL: Mutex<RefCell<Option<Uart<UART0>>>> = Mutex::new(RefCell::new(None));
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
let mut rtc = Rtc::new(peripherals.RTC_CNTL);
let mut serial0 = Serial::new(peripherals.UART0);
let mut serial0 = Uart::new(peripherals.UART0);
let timer_group0 = TimerGroup::new(peripherals.TIMG0, &clocks);
let mut timer0 = timer_group0.timer0;
let mut wdt0 = timer_group0.wdt;
@ -54,7 +54,11 @@ fn main() -> ! {
critical_section::with(|cs| SERIAL.borrow_ref_mut(cs).replace(serial0));
interrupt::enable(pac::Interrupt::UART0, interrupt::Priority::Priority1).unwrap();
interrupt::enable(
peripherals::Interrupt::UART0,
interrupt::Priority::Priority1,
)
.unwrap();
interrupt::set_kind(
Cpu::ProCpu,
interrupt::CpuInterrupt::Interrupt1, // Interrupt 1 handles priority one interrupts

View File

@ -1,26 +1,26 @@
//! Demonstrates the use of the SHA peripheral and compares the speed of hardware-accelerated and pure software hashing.
//!
//! Demonstrates the use of the SHA peripheral and compares the speed of
//! hardware-accelerated and pure software hashing.
#![no_std]
#![no_main]
use esp32c3_hal::{
clock::ClockControl,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
sha::{Sha, ShaMode},
timer::TimerGroup,
Rtc,
sha::{Sha, ShaMode},
};
use nb::block;
use esp_backtrace as _;
use esp_println::println;
use nb::block;
use riscv_rt::entry;
use sha2::{Sha256, Digest};
use sha2::{Digest, Sha256};
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -32,48 +32,51 @@ fn main() -> ! {
wdt.disable();
rtc.rwdt.disable();
let source_data = "aaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaa".as_bytes();
let mut remaining = source_data.clone();
let mut hasher = Sha::new(peripherals.SHA, ShaMode::SHA256);
// Short hashes can be created by decreasing the output buffer to the desired length
// Short hashes can be created by decreasing the output buffer to the desired
// length
let mut output = [0u8; 32];
//let pre_calc = xtensa_lx::timer::get_cycle_count();
// The hardware implementation takes a subslice of the input, and returns the unprocessed parts
// The unprocessed parts can be input in the next iteration, you can always add more data until
// finish() is called. After finish() is called update()'s will contribute to a new hash which
// let pre_calc = xtensa_lx::timer::get_cycle_count();
// The hardware implementation takes a subslice of the input, and returns the
// unprocessed parts The unprocessed parts can be input in the next
// iteration, you can always add more data until finish() is called. After
// finish() is called update()'s will contribute to a new hash which
// can be extracted again with finish().
while remaining.len() > 0 {
// Can add println to view progress, however println takes a few orders of magnitude longer than
// the Sha function itself so not useful for comparing processing time
// println!("Remaining len: {}", remaining.len());
// All the HW Sha functions are infallible so unwrap is fine to use if you use block!
while remaining.len() > 0 {
// Can add println to view progress, however println takes a few orders of
// magnitude longer than the Sha function itself so not useful for
// comparing processing time println!("Remaining len: {}",
// remaining.len());
// All the HW Sha functions are infallible so unwrap is fine to use if you use
// block!
remaining = block!(hasher.update(remaining)).unwrap();
}
// Finish can be called as many times as desired to get mutliple copies of the output.
// Finish can be called as many times as desired to get mutliple copies of the
// output.
block!(hasher.finish(output.as_mut_slice())).unwrap();
//let post_calc = xtensa_lx::timer::get_cycle_count();
//let hw_time = post_calc - pre_calc;
//println!("Took {} cycles", hw_time);
// let post_calc = xtensa_lx::timer::get_cycle_count();
// let hw_time = post_calc - pre_calc;
// println!("Took {} cycles", hw_time);
println!("SHA256 Hash output {:02x?}", output);
let _usha = hasher.free();
//let pre_calc = xtensa_lx::timer::get_cycle_count();
// let pre_calc = xtensa_lx::timer::get_cycle_count();
let mut hasher = Sha256::new();
hasher.update(source_data);
let soft_result = hasher.finalize();
//let post_calc = xtensa_lx::timer::get_cycle_count();
//let soft_time = post_calc - pre_calc;
//println!("Took {} cycles", soft_time);
// let post_calc = xtensa_lx::timer::get_cycle_count();
// let soft_time = post_calc - pre_calc;
// println!("Took {} cycles", soft_time);
println!("SHA256 Hash output {:02x?}", soft_result);
//println!("HW SHA is {}x faster", soft_time/hw_time);
// println!("HW SHA is {}x faster", soft_time/hw_time);
loop {}
}

View File

@ -22,7 +22,7 @@ use embedded_hal_1::spi::SpiDevice;
use esp32c3_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
spi::{Spi, SpiBusController, SpiMode},
timer::TimerGroup,
@ -35,7 +35,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -20,7 +20,7 @@ use embedded_hal_1::spi::SpiBus;
use esp32c3_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
spi::{Spi, SpiMode},
timer::TimerGroup,
@ -33,7 +33,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -19,7 +19,7 @@
use esp32c3_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
spi::{Spi, SpiMode},
timer::TimerGroup,
@ -32,7 +32,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -18,10 +18,10 @@
use esp32c3_hal::{
clock::ClockControl,
dma::{DmaPriority},
dma::DmaPriority,
gdma::Gdma,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
spi::{Spi, SpiMode},
timer::TimerGroup,
@ -34,7 +34,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let mut system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -11,7 +11,7 @@ use esp32c3_hal::{
clock::ClockControl,
interrupt,
interrupt::Priority,
pac::{self, Peripherals},
peripherals::{self, Peripherals},
prelude::*,
systimer::{Alarm, Periodic, SystemTimer, Target},
timer::TimerGroup,
@ -28,7 +28,7 @@ static ALARM2: Mutex<RefCell<Option<Alarm<Target, 2>>>> = Mutex::new(RefCell::ne
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -63,9 +63,21 @@ fn main() -> ! {
ALARM2.borrow_ref_mut(cs).replace(alarm2);
});
interrupt::enable(pac::Interrupt::SYSTIMER_TARGET0, Priority::Priority1).unwrap();
interrupt::enable(pac::Interrupt::SYSTIMER_TARGET1, Priority::Priority2).unwrap();
interrupt::enable(pac::Interrupt::SYSTIMER_TARGET2, Priority::Priority2).unwrap();
interrupt::enable(
peripherals::Interrupt::SYSTIMER_TARGET0,
Priority::Priority1,
)
.unwrap();
interrupt::enable(
peripherals::Interrupt::SYSTIMER_TARGET1,
Priority::Priority2,
)
.unwrap();
interrupt::enable(
peripherals::Interrupt::SYSTIMER_TARGET2,
Priority::Priority2,
)
.unwrap();
// Initialize the Delay peripheral, and use it to toggle the LED state in a
// loop.

View File

@ -11,7 +11,7 @@ use critical_section::Mutex;
use esp32c3_hal::{
clock::ClockControl,
interrupt,
pac::{self, Peripherals, TIMG0, TIMG1},
peripherals::{self, Peripherals, TIMG0, TIMG1},
prelude::*,
timer::{Timer, Timer0, TimerGroup},
Rtc,
@ -24,7 +24,7 @@ static TIMER1: Mutex<RefCell<Option<Timer<Timer0<TIMG1>>>>> = Mutex::new(RefCell
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -43,11 +43,19 @@ fn main() -> ! {
wdt0.disable();
wdt1.disable();
interrupt::enable(pac::Interrupt::TG0_T0_LEVEL, interrupt::Priority::Priority1).unwrap();
interrupt::enable(
peripherals::Interrupt::TG0_T0_LEVEL,
interrupt::Priority::Priority1,
)
.unwrap();
timer0.start(500u64.millis());
timer0.listen();
interrupt::enable(pac::Interrupt::TG1_T0_LEVEL, interrupt::Priority::Priority1).unwrap();
interrupt::enable(
peripherals::Interrupt::TG1_T0_LEVEL,
interrupt::Priority::Priority1,
)
.unwrap();
timer1.start(1u64.secs());
timer1.listen();

View File

@ -12,7 +12,7 @@ use critical_section::Mutex;
use esp32c3_hal::{
clock::ClockControl,
interrupt,
pac::{self, Peripherals, USB_DEVICE},
peripherals::{self, Peripherals, USB_DEVICE},
prelude::*,
timer::TimerGroup,
Cpu,
@ -28,7 +28,7 @@ static USB_SERIAL: Mutex<RefCell<Option<UsbSerialJtag<USB_DEVICE>>>> =
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -54,7 +54,7 @@ fn main() -> ! {
critical_section::with(|cs| USB_SERIAL.borrow_ref_mut(cs).replace(usb_serial));
interrupt::enable(
pac::Interrupt::USB_SERIAL_JTAG,
peripherals::Interrupt::USB_SERIAL_JTAG,
interrupt::Priority::Priority1,
)
.unwrap();

View File

@ -5,7 +5,13 @@
#![no_std]
#![no_main]
use esp32c3_hal::{clock::ClockControl, pac::Peripherals, prelude::*, timer::TimerGroup, Rtc};
use esp32c3_hal::{
clock::ClockControl,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Rtc,
};
use esp_backtrace as _;
use esp_println::println;
use nb::block;
@ -13,7 +19,7 @@ use riscv_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();

View File

@ -5,6 +5,8 @@ use core::arch::{asm, global_asm};
use core::mem::size_of;
pub use embedded_hal as ehal;
#[cfg(feature = "embassy")]
pub use esp_hal_common::embassy;
#[doc(inline)]
pub use esp_hal_common::{
analog::adc::implementation as adc,
@ -18,14 +20,15 @@ pub use esp_hal_common::{
interrupt,
ledc,
macros,
pac,
peripherals,
prelude,
pulse_control,
serial,
sha,
spi,
system,
systimer,
timer,
uart,
utils,
Cpu,
Delay,
@ -33,14 +36,9 @@ pub use esp_hal_common::{
Rng,
Rtc,
Rwdt,
Serial,
Uart,
UsbSerialJtag,
sha
};
#[cfg(feature = "embassy")]
pub use esp_hal_common::embassy;
#[cfg(feature = "direct-boot")]
use riscv_rt::pre_init;
@ -407,7 +405,7 @@ unsafe fn configure_mmu() {
0,
);
let peripherals = pac::Peripherals::steal();
let peripherals = peripherals::Peripherals::steal();
peripherals.EXTMEM.icache_ctrl1.modify(|_, w| {
w.icache_shut_ibus()
.clear_bit()
@ -444,4 +442,4 @@ pub fn mp_hook() -> bool {
}
#[no_mangle]
extern "C" fn EspDefaultHandler(_interrupt: pac::Interrupt) {}
extern "C" fn EspDefaultHandler(_interrupt: peripherals::Interrupt) {}

View File

@ -9,20 +9,20 @@ use esp32s2_hal::{
adc::{AdcConfig, Attenuation, ADC, ADC1},
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Delay,
Rtc,
};
use esp_backtrace as _;
use xtensa_atomic_emulation_trap as _;
use esp_println::println;
use xtensa_atomic_emulation_trap as _;
use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -57,15 +57,18 @@ fn main() -> ! {
}
#[xtensa_lx_rt::exception]
fn exception(cause: xtensa_lx_rt::exception::ExceptionCause, frame: xtensa_lx_rt::exception::Context) {
fn exception(
cause: xtensa_lx_rt::exception::ExceptionCause,
frame: xtensa_lx_rt::exception::Context,
) {
use esp_println::*;
println!("\n\nException occured {:?} {:x?}", cause, frame);
let backtrace = esp_backtrace::arch::backtrace();
for b in backtrace.iter() {
if let Some(addr) = b {
println!("0x{:x}", addr)
}
}
}
}

View File

@ -9,26 +9,26 @@
use esp32s2_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
serial::{
timer::TimerGroup,
uart::{
config::{Config, DataBits, Parity, StopBits},
TxRxPins,
},
timer::TimerGroup,
Delay,
Rtc,
Serial,
Uart,
};
use esp_backtrace as _;
use xtensa_atomic_emulation_trap as _;
use esp_println::println;
use nb::block;
use xtensa_atomic_emulation_trap as _;
use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -53,7 +53,7 @@ fn main() -> ! {
io.pins.gpio2.into_floating_input(),
);
let mut serial1 = Serial::new_with_config(peripherals.UART1, Some(config), Some(pins), &clocks);
let mut serial1 = Uart::new_with_config(peripherals.UART1, Some(config), Some(pins), &clocks);
let mut delay = Delay::new(&clocks);
@ -72,15 +72,18 @@ fn main() -> ! {
}
#[xtensa_lx_rt::exception]
fn exception(cause: xtensa_lx_rt::exception::ExceptionCause, frame: xtensa_lx_rt::exception::Context) {
fn exception(
cause: xtensa_lx_rt::exception::ExceptionCause,
frame: xtensa_lx_rt::exception::Context,
) {
use esp_println::*;
println!("\n\nException occured {:?} {:x?}", cause, frame);
let backtrace = esp_backtrace::arch::backtrace();
for b in backtrace.iter() {
if let Some(addr) = b {
println!("0x{:x}", addr)
}
}
}
}

View File

@ -8,7 +8,7 @@
use esp32s2_hal::{
clock::ClockControl,
gpio::IO,
pac::Peripherals,
peripherals::Peripherals,
prelude::*,
timer::TimerGroup,
Delay,
@ -20,7 +20,7 @@ use xtensa_lx_rt::entry;
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -49,15 +49,18 @@ fn main() -> ! {
}
#[xtensa_lx_rt::exception]
fn exception(cause: xtensa_lx_rt::exception::ExceptionCause, frame: xtensa_lx_rt::exception::Context) {
fn exception(
cause: xtensa_lx_rt::exception::ExceptionCause,
frame: xtensa_lx_rt::exception::Context,
) {
use esp_println::*;
println!("\n\nException occured {:?} {:x?}", cause, frame);
let backtrace = esp_backtrace::arch::backtrace();
for b in backtrace.iter() {
if let Some(addr) = b {
println!("0x{:x}", addr)
}
}
}
}

View File

@ -11,20 +11,20 @@ use critical_section::Mutex;
use esp32s2_hal::{
clock::ClockControl,
interrupt,
pac::{self, Peripherals},
peripherals::{self, Peripherals},
prelude::*,
Rtc,
};
use esp_backtrace as _;
use xtensa_atomic_emulation_trap as _;
use esp_println::println;
use xtensa_atomic_emulation_trap as _;
use xtensa_lx_rt::entry;
static RTC: Mutex<RefCell<Option<Rtc>>> = Mutex::new(RefCell::new(None));
#[entry]
fn main() -> ! {
let peripherals = Peripherals::take().unwrap();
let peripherals = Peripherals::take();
let system = peripherals.SYSTEM.split();
let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
@ -42,7 +42,11 @@ fn main() -> ! {
clocks.xtal_clock.to_MHz()
);
interrupt::enable(pac::Interrupt::RTC_CORE, interrupt::Priority::Priority1).unwrap();
interrupt::enable(
peripherals::Interrupt::RTC_CORE,
interrupt::Priority::Priority1,
)
.unwrap();
critical_section::with(|cs| RTC.borrow_ref_mut(cs).replace(rtc));
@ -66,15 +70,18 @@ fn RTC_CORE() {
}
#[xtensa_lx_rt::exception]
fn exception(cause: xtensa_lx_rt::exception::ExceptionCause, frame: xtensa_lx_rt::exception::Context) {
fn exception(
cause: xtensa_lx_rt::exception::ExceptionCause,
frame: xtensa_lx_rt::exception::Context,
) {
use esp_println::*;
println!("\n\nException occured {:?} {:x?}", cause, frame);
let backtrace = esp_backtrace::arch::backtrace();
for b in backtrace.iter() {
if let Some(addr) = b {
println!("0x{:x}", addr)
}
}
}
}

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