Move all peripheral generics into the constructors

This commit is contained in:
ivmarkov 2022-11-01 10:00:24 +02:00
parent 59629c8b49
commit d6370068ef
10 changed files with 296 additions and 262 deletions

View File

@ -7,9 +7,7 @@
//! Depending on your target and the board you are using you should change the pins. //! Depending on your target and the board you are using you should change the pins.
//! If your board doesn't have on-board LEDs don't forget to add an appropriate resistor. //! If your board doesn't have on-board LEDs don't forget to add an appropriate resistor.
use std::thread; use esp_idf_hal::delay::FreeRtos;
use std::time::Duration;
use esp_idf_hal::gpio::*; use esp_idf_hal::gpio::*;
use esp_idf_hal::peripherals::Peripherals; use esp_idf_hal::peripherals::Peripherals;
@ -24,7 +22,7 @@ fn main() -> anyhow::Result<()> {
loop { loop {
// we are using thread::sleep here to make sure the watchdog isn't triggered // we are using thread::sleep here to make sure the watchdog isn't triggered
thread::sleep(Duration::from_millis(10)); FreeRtos::delay_ms(10);
if button.is_high() { if button.is_high() {
led.set_low()?; led.set_low()?;

View File

@ -65,11 +65,11 @@ fn main() -> anyhow::Result<()> {
} }
fn send_morse_code<'d>( fn send_morse_code<'d>(
channel: impl Peripheral<P = CHANNEL0> + 'd, channel: impl Peripheral<P = impl RmtChannel> + 'd,
led: impl Peripheral<P = impl OutputPin> + 'd, led: impl Peripheral<P = impl OutputPin> + 'd,
config: &TransmitConfig, config: &TransmitConfig,
message: &str, message: &str,
) -> anyhow::Result<RmtDriver<'d, CHANNEL0>> { ) -> anyhow::Result<RmtDriver<'d>> {
println!("Sending morse message '{}'.", message); println!("Sending morse message '{}'.", message);
let mut signal = VariableLengthSignal::new(); let mut signal = VariableLengthSignal::new();

View File

@ -20,7 +20,7 @@ fn main() -> anyhow::Result<()> {
let led = peripherals.pins.gpio17; let led = peripherals.pins.gpio17;
let channel = peripherals.rmt.channel0; let channel = peripherals.rmt.channel0;
let config = TransmitConfig::new().looping(Loop::Endless); let config = TransmitConfig::new().looping(Loop::Endless);
let mut tx: RmtDriver<'static, _> = RmtDriver::new(channel, led, &config)?; let mut tx: RmtDriver<'static> = RmtDriver::new(channel, led, &config)?;
loop { loop {
play_song(&mut tx, ODE_TO_JOY)?; play_song(&mut tx, ODE_TO_JOY)?;
@ -28,10 +28,7 @@ fn main() -> anyhow::Result<()> {
} }
} }
pub fn play_song( pub fn play_song(tx: &mut RmtDriver<'static>, song: &[NoteValue]) -> anyhow::Result<()> {
tx: &mut RmtDriver<'static, impl RmtChannel>,
song: &[NoteValue],
) -> anyhow::Result<()> {
for note_value in song { for note_value in song {
play_note(tx, note_value.note.0, note_value.duration)?; play_note(tx, note_value.note.0, note_value.duration)?;
} }
@ -39,7 +36,7 @@ pub fn play_song(
} }
pub fn play_note( pub fn play_note(
tx: &mut RmtDriver<'static, impl RmtChannel>, tx: &mut RmtDriver<'static>,
pitch: u16, pitch: u16,
duration: Duration, duration: Duration,
) -> anyhow::Result<()> { ) -> anyhow::Result<()> {

View File

@ -11,11 +11,9 @@
//! This example transfers data via SPI. //! This example transfers data via SPI.
//! Connect SDI and SDO pins to see the outgoing data is read as incoming data. //! Connect SDI and SDO pins to see the outgoing data is read as incoming data.
use std::thread;
use std::time::Duration;
use embedded_hal::spi::SpiDevice; use embedded_hal::spi::SpiDevice;
use esp_idf_hal::delay::FreeRtos;
use esp_idf_hal::peripherals::Peripherals; use esp_idf_hal::peripherals::Peripherals;
use esp_idf_hal::prelude::*; use esp_idf_hal::prelude::*;
use esp_idf_hal::spi::*; use esp_idf_hal::spi::*;
@ -34,14 +32,14 @@ fn main() -> anyhow::Result<()> {
println!("Starting SPI loopback test"); println!("Starting SPI loopback test");
let config = config::Config::new().baudrate(26.MHz().into()); let config = config::Config::new().baudrate(26.MHz().into());
let mut spi = let mut spi =
SpiMasterDriver::<SPI2>::new(spi, sclk, serial_out, Some(serial_in), Some(cs), &config)?; SpiMasterDriver::new::<SPI2>(spi, sclk, serial_out, Some(serial_in), Some(cs), &config)?;
let mut read = [0u8; 4]; let mut read = [0u8; 4];
let write = [0xde, 0xad, 0xbe, 0xef]; let write = [0xde, 0xad, 0xbe, 0xef];
loop { loop {
// we are using thread::sleep here to make sure the watchdog isn't triggered // we are using thread::sleep here to make sure the watchdog isn't triggered
thread::sleep(Duration::from_millis(500)); FreeRtos::delay_ms(500);
spi.transfer(&mut read, &write)?; spi.transfer(&mut read, &write)?;
println!("Wrote {:x?}, read {:x?}", write, read); println!("Wrote {:x?}, read {:x?}", write, read);
} }

View File

@ -6,7 +6,7 @@ use esp_idf_sys::*;
use crate::delay::*; use crate::delay::*;
use crate::gpio::*; use crate::gpio::*;
use crate::peripheral::{Peripheral, PeripheralRef}; use crate::peripheral::Peripheral;
use crate::units::*; use crate::units::*;
pub use embedded_hal::i2c::Operation; pub use embedded_hal::i2c::Operation;
@ -121,29 +121,24 @@ pub trait I2c: Send {
fn port() -> i2c_port_t; fn port() -> i2c_port_t;
} }
pub struct I2cMasterDriver<'d, I2C> pub struct I2cMasterDriver<'d> {
where i2c: u8,
I2C: I2c, _p: PhantomData<&'d ()>,
{
_i2c: PeripheralRef<'d, I2C>,
} }
impl<'d, I2C> I2cMasterDriver<'d, I2C> impl<'d> I2cMasterDriver<'d> {
where pub fn new<I2C: I2c>(
I2C: I2c, _i2c: impl Peripheral<P = I2C> + 'd,
{
pub fn new(
i2c: impl Peripheral<P = I2C> + 'd,
sda: impl Peripheral<P = impl InputPin + OutputPin> + 'd, sda: impl Peripheral<P = impl InputPin + OutputPin> + 'd,
scl: impl Peripheral<P = impl InputPin + OutputPin> + 'd, scl: impl Peripheral<P = impl InputPin + OutputPin> + 'd,
config: &config::MasterConfig, config: &config::MasterConfig,
) -> Result<I2cMasterDriver<'d, I2C>, EspError> { ) -> Result<Self, EspError> {
// i2c_config_t documentation says that clock speed must be no higher than 1 MHz // i2c_config_t documentation says that clock speed must be no higher than 1 MHz
if config.baudrate > 1.MHz().into() { if config.baudrate > 1.MHz().into() {
return Err(EspError::from(ESP_ERR_INVALID_ARG).unwrap()); return Err(EspError::from(ESP_ERR_INVALID_ARG).unwrap());
} }
crate::into_ref!(i2c, sda, scl); crate::into_ref!(sda, scl);
let sys_config = i2c_config_t { let sys_config = i2c_config_t {
mode: i2c_mode_t_I2C_MODE_MASTER, mode: i2c_mode_t_I2C_MODE_MASTER,
@ -171,7 +166,10 @@ where
) // TODO: set flags ) // TODO: set flags
})?; })?;
Ok(I2cMasterDriver { _i2c: i2c }) Ok(I2cMasterDriver {
i2c: I2C::port() as _,
_p: PhantomData,
})
} }
pub fn read( pub fn read(
@ -297,22 +295,23 @@ where
command_link: &CommandLink, command_link: &CommandLink,
timeout: TickType_t, timeout: TickType_t,
) -> Result<(), EspError> { ) -> Result<(), EspError> {
esp!(unsafe { i2c_master_cmd_begin(I2C::port(), command_link.0, timeout) }) esp!(unsafe { i2c_master_cmd_begin(self.port(), command_link.0, timeout) })
}
pub fn port(&self) -> i2c_port_t {
self.i2c as _
} }
} }
impl<'d, I2C: I2c> Drop for I2cMasterDriver<'d, I2C> { impl<'d> Drop for I2cMasterDriver<'d> {
fn drop(&mut self) { fn drop(&mut self) {
esp!(unsafe { i2c_driver_delete(I2C::port()) }).unwrap(); esp!(unsafe { i2c_driver_delete(self.port()) }).unwrap();
} }
} }
unsafe impl<'d, I2C: I2c> Send for I2cMasterDriver<'d, I2C> {} unsafe impl<'d> Send for I2cMasterDriver<'d> {}
impl<'d, I2C> embedded_hal_0_2::blocking::i2c::Read for I2cMasterDriver<'d, I2C> impl<'d> embedded_hal_0_2::blocking::i2c::Read for I2cMasterDriver<'d> {
where
I2C: I2c,
{
type Error = I2cError; type Error = I2cError;
fn read(&mut self, addr: u8, buffer: &mut [u8]) -> Result<(), Self::Error> { fn read(&mut self, addr: u8, buffer: &mut [u8]) -> Result<(), Self::Error> {
@ -320,10 +319,7 @@ where
} }
} }
impl<'d, I2C> embedded_hal_0_2::blocking::i2c::Write for I2cMasterDriver<'d, I2C> impl<'d> embedded_hal_0_2::blocking::i2c::Write for I2cMasterDriver<'d> {
where
I2C: I2c,
{
type Error = I2cError; type Error = I2cError;
fn write(&mut self, addr: u8, bytes: &[u8]) -> Result<(), Self::Error> { fn write(&mut self, addr: u8, bytes: &[u8]) -> Result<(), Self::Error> {
@ -331,10 +327,7 @@ where
} }
} }
impl<'d, I2C> embedded_hal_0_2::blocking::i2c::WriteRead for I2cMasterDriver<'d, I2C> impl<'d> embedded_hal_0_2::blocking::i2c::WriteRead for I2cMasterDriver<'d> {
where
I2C: I2c,
{
type Error = I2cError; type Error = I2cError;
fn write_read(&mut self, addr: u8, bytes: &[u8], buffer: &mut [u8]) -> Result<(), Self::Error> { fn write_read(&mut self, addr: u8, bytes: &[u8], buffer: &mut [u8]) -> Result<(), Self::Error> {
@ -342,18 +335,11 @@ where
} }
} }
impl<'d, I2C> embedded_hal::i2c::ErrorType for I2cMasterDriver<'d, I2C> impl<'d> embedded_hal::i2c::ErrorType for I2cMasterDriver<'d> {
where
I2C: I2c,
{
type Error = I2cError; type Error = I2cError;
} }
impl<'d, I2C> embedded_hal::i2c::I2c<embedded_hal::i2c::SevenBitAddress> impl<'d> embedded_hal::i2c::I2c<embedded_hal::i2c::SevenBitAddress> for I2cMasterDriver<'d> {
for I2cMasterDriver<'d, I2C>
where
I2C: I2c,
{
fn read(&mut self, addr: u8, buffer: &mut [u8]) -> Result<(), Self::Error> { fn read(&mut self, addr: u8, buffer: &mut [u8]) -> Result<(), Self::Error> {
I2cMasterDriver::read(self, addr, buffer, BLOCK).map_err(to_i2c_err) I2cMasterDriver::read(self, addr, buffer, BLOCK).map_err(to_i2c_err)
} }
@ -409,27 +395,22 @@ fn to_i2c_err(err: EspError) -> I2cError {
} }
} }
pub struct I2cSlaveDriver<'d, I2C> pub struct I2cSlaveDriver<'d> {
where i2c: u8,
I2C: I2c, _p: PhantomData<&'d ()>,
{
_i2c: PeripheralRef<'d, I2C>,
} }
unsafe impl<'d, I2C: I2c> Send for I2cSlaveDriver<'d, I2C> {} unsafe impl<'d> Send for I2cSlaveDriver<'d> {}
impl<'d, I2C> I2cSlaveDriver<'d, I2C> impl<'d> I2cSlaveDriver<'d> {
where pub fn new<I2C: I2c>(
I2C: I2c, _i2c: impl Peripheral<P = I2C> + 'd,
{
pub fn new(
i2c: impl Peripheral<P = I2C> + 'd,
sda: impl Peripheral<P = impl InputPin + OutputPin> + 'd, sda: impl Peripheral<P = impl InputPin + OutputPin> + 'd,
scl: impl Peripheral<P = impl InputPin + OutputPin> + 'd, scl: impl Peripheral<P = impl InputPin + OutputPin> + 'd,
slave_addr: u8, slave_addr: u8,
config: &config::SlaveConfig, config: &config::SlaveConfig,
) -> Result<Self, EspError> { ) -> Result<Self, EspError> {
crate::into_ref!(i2c, sda, scl); crate::into_ref!(sda, scl);
#[cfg(not(esp_idf_version = "4.3"))] #[cfg(not(esp_idf_version = "4.3"))]
let sys_config = i2c_config_t { let sys_config = i2c_config_t {
@ -476,13 +457,16 @@ where
) )
})?; })?;
Ok(Self { _i2c: i2c }) Ok(Self {
i2c: I2C::port() as _,
_p: PhantomData,
})
} }
pub fn read(&mut self, buffer: &mut [u8], timeout: TickType_t) -> Result<usize, EspError> { pub fn read(&mut self, buffer: &mut [u8], timeout: TickType_t) -> Result<usize, EspError> {
let n = unsafe { let n = unsafe {
i2c_slave_read_buffer( i2c_slave_read_buffer(
I2C::port(), self.port(),
buffer.as_mut_ptr(), buffer.as_mut_ptr(),
buffer.len() as u32, buffer.len() as u32,
timeout, timeout,
@ -499,7 +483,7 @@ where
pub fn write(&mut self, bytes: &[u8], timeout: TickType_t) -> Result<usize, EspError> { pub fn write(&mut self, bytes: &[u8], timeout: TickType_t) -> Result<usize, EspError> {
let n = unsafe { let n = unsafe {
i2c_slave_write_buffer( i2c_slave_write_buffer(
I2C::port(), self.port(),
bytes.as_ptr() as *const u8 as *mut u8, bytes.as_ptr() as *const u8 as *mut u8,
bytes.len() as i32, bytes.len() as i32,
timeout, timeout,
@ -512,6 +496,16 @@ where
Err(EspError::from(ESP_ERR_TIMEOUT).unwrap()) Err(EspError::from(ESP_ERR_TIMEOUT).unwrap())
} }
} }
pub fn port(&self) -> i2c_port_t {
self.i2c as _
}
}
impl<'d> Drop for I2cSlaveDriver<'d> {
fn drop(&mut self) {
esp!(unsafe { i2c_driver_delete(self.port()) }).unwrap();
}
} }
#[repr(u32)] #[repr(u32)]

View File

@ -24,12 +24,13 @@
//! See the `examples/` folder of this repository for more. //! See the `examples/` folder of this repository for more.
use core::borrow::Borrow; use core::borrow::Borrow;
use core::marker::PhantomData;
use core::sync::atomic::{AtomicBool, Ordering}; use core::sync::atomic::{AtomicBool, Ordering};
use esp_idf_sys::*; use esp_idf_sys::*;
use crate::gpio::OutputPin; use crate::gpio::OutputPin;
use crate::peripheral::{Peripheral, PeripheralRef}; use crate::peripheral::Peripheral;
use crate::task::CriticalSection; use crate::task::CriticalSection;
pub use chip::*; pub use chip::*;
@ -92,19 +93,18 @@ pub mod config {
} }
/// LED Control timer driver /// LED Control timer driver
pub struct LedcTimerDriver<'d, T: LedcTimer> { pub struct LedcTimerDriver<'d> {
_timer: PeripheralRef<'d, T>, timer: u8,
speed_mode: ledc_mode_t, speed_mode: ledc_mode_t,
max_duty: Duty, max_duty: Duty,
_p: PhantomData<&'d ()>,
} }
impl<'d, T: LedcTimer> LedcTimerDriver<'d, T> { impl<'d> LedcTimerDriver<'d> {
pub fn new( pub fn new<T: LedcTimer>(
timer: impl Peripheral<P = T> + 'd, _timer: impl Peripheral<P = T> + 'd,
config: &config::TimerConfig, config: &config::TimerConfig,
) -> Result<Self, EspError> { ) -> Result<Self, EspError> {
crate::into_ref!(timer);
let timer_config = ledc_timer_config_t { let timer_config = ledc_timer_config_t {
speed_mode: config.speed_mode, speed_mode: config.speed_mode,
timer_num: T::timer(), timer_num: T::timer(),
@ -122,67 +122,66 @@ impl<'d, T: LedcTimer> LedcTimerDriver<'d, T> {
esp!(unsafe { ledc_timer_config(&timer_config) })?; esp!(unsafe { ledc_timer_config(&timer_config) })?;
Ok(Self { Ok(Self {
_timer: timer, timer: T::timer() as _,
speed_mode: config.speed_mode, speed_mode: config.speed_mode,
max_duty: config.resolution.max_duty(), max_duty: config.resolution.max_duty(),
_p: PhantomData,
}) })
} }
/// Pauses the timer. Operation can be resumed with [`resume_timer()`]. /// Pauses the timer. Operation can be resumed with [`resume_timer()`].
pub fn pause(&mut self) -> Result<(), EspError> { pub fn pause(&mut self) -> Result<(), EspError> {
esp!(unsafe { ledc_timer_pause(self.speed_mode, T::timer()) })?; esp!(unsafe { ledc_timer_pause(self.speed_mode, self.timer()) })?;
Ok(()) Ok(())
} }
/// Resumes the operation of the previously paused timer /// Resumes the operation of the previously paused timer
pub fn resume(&mut self) -> Result<(), EspError> { pub fn resume(&mut self) -> Result<(), EspError> {
esp!(unsafe { ledc_timer_resume(self.speed_mode, T::timer()) })?; esp!(unsafe { ledc_timer_resume(self.speed_mode, self.timer()) })?;
Ok(()) Ok(())
} }
fn reset(&mut self) -> Result<(), EspError> { fn reset(&mut self) -> Result<(), EspError> {
esp!(unsafe { ledc_timer_rst(self.speed_mode, T::timer()) })?; esp!(unsafe { ledc_timer_rst(self.speed_mode, self.timer()) })?;
Ok(()) Ok(())
} }
pub fn timer(&self) -> ledc_timer_t {
self.timer as _
}
} }
impl<'d, T: LedcTimer> Drop for LedcTimerDriver<'d, T> { impl<'d> Drop for LedcTimerDriver<'d> {
fn drop(&mut self) { fn drop(&mut self) {
self.reset().unwrap(); self.reset().unwrap();
} }
} }
unsafe impl<'d, T: LedcTimer> Send for LedcTimerDriver<'d, T> {} unsafe impl<'d> Send for LedcTimerDriver<'d> {}
/// LED Control driver /// LED Control driver
pub struct LedcDriver<'d, C, B> pub struct LedcDriver<'d> {
where channel: u8,
C: LedcChannel, timer: u8,
{
_channel: PeripheralRef<'d, C>,
_timer_driver: B,
duty: Duty, duty: Duty,
hpoint: HPoint, hpoint: HPoint,
speed_mode: ledc_mode_t, speed_mode: ledc_mode_t,
max_duty: Duty, max_duty: Duty,
_p: PhantomData<&'d ()>,
} }
// TODO: Stop channel when the instance gets dropped. It seems that we can't // TODO: Stop channel when the instance gets dropped. It seems that we can't
// have both at the same time: a method for releasing its hardware resources // have both at the same time: a method for releasing its hardware resources
// and implementing Drop. // and implementing Drop.
impl<'d, C: LedcChannel, B> LedcDriver<'d, C, B> { impl<'d> LedcDriver<'d> {
/// Creates a new LED Control driver /// Creates a new LED Control driver
pub fn new<T>( pub fn new<C: LedcChannel, B: Borrow<LedcTimerDriver<'d>>>(
channel: impl Peripheral<P = C> + 'd, _channel: impl Peripheral<P = C> + 'd,
timer_driver: B, timer_driver: B,
pin: impl Peripheral<P = impl OutputPin> + 'd, pin: impl Peripheral<P = impl OutputPin> + 'd,
config: &config::TimerConfig, config: &config::TimerConfig,
) -> Result<Self, EspError> ) -> Result<Self, EspError> {
where crate::into_ref!(pin);
B: Borrow<LedcTimerDriver<'d, T>>,
T: LedcTimer + 'd,
{
crate::into_ref!(channel, pin);
let duty = 0; let duty = 0;
let hpoint = 0; let hpoint = 0;
@ -190,7 +189,7 @@ impl<'d, C: LedcChannel, B> LedcDriver<'d, C, B> {
let channel_config = ledc_channel_config_t { let channel_config = ledc_channel_config_t {
speed_mode: config.speed_mode, speed_mode: config.speed_mode,
channel: C::channel(), channel: C::channel(),
timer_sel: T::timer(), timer_sel: timer_driver.borrow().timer(),
intr_type: ledc_intr_type_t_LEDC_INTR_DISABLE, intr_type: ledc_intr_type_t_LEDC_INTR_DISABLE,
gpio_num: pin.pin(), gpio_num: pin.pin(),
duty, duty,
@ -223,8 +222,9 @@ impl<'d, C: LedcChannel, B> LedcDriver<'d, C, B> {
hpoint, hpoint,
speed_mode: timer_driver.borrow().speed_mode, speed_mode: timer_driver.borrow().speed_mode,
max_duty: timer_driver.borrow().max_duty, max_duty: timer_driver.borrow().max_duty,
_channel: channel, timer: timer_driver.borrow().timer() as _,
_timer_driver: timer_driver, channel: C::channel() as _,
_p: PhantomData,
}) })
} }
@ -270,26 +270,34 @@ impl<'d, C: LedcChannel, B> LedcDriver<'d, C, B> {
} }
fn stop(&mut self) -> Result<(), EspError> { fn stop(&mut self) -> Result<(), EspError> {
esp!(unsafe { ledc_stop(self.speed_mode, C::channel(), IDLE_LEVEL,) })?; esp!(unsafe { ledc_stop(self.speed_mode, self.channel(), IDLE_LEVEL,) })?;
Ok(()) Ok(())
} }
fn update_duty(&mut self, duty: Duty, hpoint: HPoint) -> Result<(), EspError> { fn update_duty(&mut self, duty: Duty, hpoint: HPoint) -> Result<(), EspError> {
esp!(unsafe { ledc_set_duty_and_update(self.speed_mode, C::channel(), duty, hpoint) })?; esp!(unsafe { ledc_set_duty_and_update(self.speed_mode, self.channel(), duty, hpoint) })?;
Ok(()) Ok(())
} }
pub fn channel(&self) -> ledc_channel_t {
self.channel as _
}
pub fn timer(&self) -> ledc_timer_t {
self.timer as _
}
} }
impl<'d, C: LedcChannel, B> Drop for LedcDriver<'d, C, B> { impl<'d> Drop for LedcDriver<'d> {
fn drop(&mut self) { fn drop(&mut self) {
self.stop().unwrap(); self.stop().unwrap();
} }
} }
unsafe impl<'d, C: LedcChannel, B> Send for LedcDriver<'d, C, B> {} unsafe impl<'d> Send for LedcDriver<'d> {}
// PwmPin temporarily removed from embedded-hal-1.0.alpha7 in anticipation of e-hal 1.0 release // PwmPin temporarily removed from embedded-hal-1.0.alpha7 in anticipation of e-hal 1.0 release
// impl<'d, C: LedcChannel, B: Borrow<LedcTimerDriver<'d, T>>, T: LedcTimer> embedded_hal::pwm::blocking::PwmPin for LedcDriver<'d, C, B, T> { // impl<'d> embedded_hal::pwm::blocking::PwmPin for LedcDriver<'d> {
// type Duty = Duty; // type Duty = Duty;
// type Error = EspError; // type Error = EspError;
@ -314,7 +322,7 @@ unsafe impl<'d, C: LedcChannel, B> Send for LedcDriver<'d, C, B> {}
// } // }
// } // }
impl<'d, C: LedcChannel, B> embedded_hal_0_2::PwmPin for LedcDriver<'d, C, B> { impl<'d> embedded_hal_0_2::PwmPin for LedcDriver<'d> {
type Duty = Duty; type Duty = Duty;
fn disable(&mut self) { fn disable(&mut self) {

View File

@ -52,6 +52,7 @@
//! ahead of time. //! ahead of time.
use core::convert::TryFrom; use core::convert::TryFrom;
use core::marker::PhantomData;
use core::time::Duration; use core::time::Duration;
#[cfg(feature = "alloc")] #[cfg(feature = "alloc")]
@ -64,7 +65,7 @@ use core::cell::UnsafeCell;
use esp_idf_sys::*; use esp_idf_sys::*;
use crate::gpio::OutputPin; use crate::gpio::OutputPin;
use crate::peripheral::{Peripheral, PeripheralRef}; use crate::peripheral::Peripheral;
use crate::units::Hertz; use crate::units::Hertz;
use config::TransmitConfig; use config::TransmitConfig;
@ -341,22 +342,23 @@ pub mod config {
/// Use [`RmtDriver::start()`] or [`RmtDriver::start_blocking()`] to transmit pulses. /// Use [`RmtDriver::start()`] or [`RmtDriver::start_blocking()`] to transmit pulses.
/// ///
/// See the [rmt module][crate::rmt] for more information. /// See the [rmt module][crate::rmt] for more information.
pub struct RmtDriver<'d, C: RmtChannel> { pub struct RmtDriver<'d> {
_channel: PeripheralRef<'d, C>, channel: u8,
_p: PhantomData<&'d ()>,
} }
impl<'d, C: RmtChannel> RmtDriver<'d, C> { impl<'d> RmtDriver<'d> {
/// Initialise the rmt module with the specified pin, channel and configuration. /// Initialise the rmt module with the specified pin, channel and configuration.
/// ///
/// To uninstall the driver just drop it. /// To uninstall the driver just drop it.
/// ///
/// Internally this calls `rmt_config()` and `rmt_driver_install()`. /// Internally this calls `rmt_config()` and `rmt_driver_install()`.
pub fn new( pub fn new<C: RmtChannel>(
channel: impl Peripheral<P = C> + 'd, _channel: impl Peripheral<P = C> + 'd,
pin: impl Peripheral<P = impl OutputPin> + 'd, pin: impl Peripheral<P = impl OutputPin> + 'd,
config: &TransmitConfig, config: &TransmitConfig,
) -> Result<Self, EspError> { ) -> Result<Self, EspError> {
crate::into_ref!(channel, pin); crate::into_ref!(pin);
let mut flags = 0; let mut flags = 0;
if config.aware_dfs { if config.aware_dfs {
@ -396,7 +398,10 @@ impl<'d, C: RmtChannel> RmtDriver<'d, C> {
esp!(rmt_driver_install(C::channel(), 0, 0))?; esp!(rmt_driver_install(C::channel(), 0, 0))?;
} }
Ok(Self { _channel: channel }) Ok(Self {
channel: C::channel() as _,
_p: PhantomData,
})
} }
/// Get speed of the channels internal counter clock. /// Get speed of the channels internal counter clock.
@ -409,7 +414,7 @@ impl<'d, C: RmtChannel> RmtDriver<'d, C> {
/// [rmt_get_counter_clock]: https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/peripherals/rmt.html#_CPPv421rmt_get_counter_clock13rmt_channel_tP8uint32_t /// [rmt_get_counter_clock]: https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/peripherals/rmt.html#_CPPv421rmt_get_counter_clock13rmt_channel_tP8uint32_t
pub fn counter_clock(&self) -> Result<Hertz, EspError> { pub fn counter_clock(&self) -> Result<Hertz, EspError> {
let mut ticks_hz: u32 = 0; let mut ticks_hz: u32 = 0;
esp!(unsafe { rmt_get_counter_clock(C::channel(), &mut ticks_hz) })?; esp!(unsafe { rmt_get_counter_clock(self.channel(), &mut ticks_hz) })?;
Ok(ticks_hz.into()) Ok(ticks_hz.into())
} }
@ -436,7 +441,7 @@ impl<'d, C: RmtChannel> RmtDriver<'d, C> {
S: Signal, S: Signal,
{ {
let items = signal.as_slice(); let items = signal.as_slice();
esp!(unsafe { rmt_write_items(C::channel(), items.as_ptr(), items.len() as i32, block) }) esp!(unsafe { rmt_write_items(self.channel(), items.as_ptr(), items.len() as i32, block) })
} }
/// Transmit all items in `iter` without blocking. /// Transmit all items in `iter` without blocking.
@ -458,12 +463,12 @@ impl<'d, C: RmtChannel> RmtDriver<'d, C> {
let iter = Box::new(UnsafeCell::new(iter)); let iter = Box::new(UnsafeCell::new(iter));
unsafe { unsafe {
esp!(rmt_translator_init( esp!(rmt_translator_init(
C::channel(), self.channel(),
Some(Self::translate_iterator::<T, true>), Some(Self::translate_iterator::<T, true>),
))?; ))?;
esp!(rmt_write_sample( esp!(rmt_write_sample(
C::channel(), self.channel(),
Box::leak(iter) as *const _ as _, Box::leak(iter) as *const _ as _,
1, 1,
false false
@ -493,11 +498,11 @@ impl<'d, C: RmtChannel> RmtDriver<'d, C> {
// TODO: maybe use a separate struct so that we don't have to do this when // TODO: maybe use a separate struct so that we don't have to do this when
// transmitting the same iterator type. // transmitting the same iterator type.
esp!(rmt_translator_init( esp!(rmt_translator_init(
C::channel(), self.channel(),
Some(Self::translate_iterator::<T, false>), Some(Self::translate_iterator::<T, false>),
))?; ))?;
esp!(rmt_write_sample( esp!(rmt_write_sample(
C::channel(), self.channel(),
&iter as *const _ as _, &iter as *const _ as _,
24, 24,
true true
@ -563,16 +568,16 @@ impl<'d, C: RmtChannel> RmtDriver<'d, C> {
/// Stop transmitting. /// Stop transmitting.
pub fn stop(&mut self) -> Result<(), EspError> { pub fn stop(&mut self) -> Result<(), EspError> {
esp!(unsafe { rmt_tx_stop(C::channel()) }) esp!(unsafe { rmt_tx_stop(self.channel()) })
} }
pub fn set_looping(&mut self, looping: config::Loop) -> Result<(), EspError> { pub fn set_looping(&mut self, looping: config::Loop) -> Result<(), EspError> {
esp!(unsafe { rmt_set_tx_loop_mode(C::channel(), looping != config::Loop::None) })?; esp!(unsafe { rmt_set_tx_loop_mode(self.channel(), looping != config::Loop::None) })?;
#[cfg(not(any(esp32, esp32c2)))] #[cfg(not(any(esp32, esp32c2)))]
esp!(unsafe { esp!(unsafe {
rmt_set_tx_loop_count( rmt_set_tx_loop_count(
C::channel(), self.channel(),
match looping { match looping {
config::Loop::Count(count) if count > 0 && count < 1024 => count, config::Loop::Count(count) if count > 0 && count < 1024 => count,
_ => 0, _ => 0,
@ -582,17 +587,21 @@ impl<'d, C: RmtChannel> RmtDriver<'d, C> {
Ok(()) Ok(())
} }
}
impl<'d, C: RmtChannel> Drop for RmtDriver<'d, C> { pub fn channel(&self) -> rmt_channel_t {
/// Stop transmitting and release the driver. self.channel as _
fn drop(&mut self) {
self.stop().unwrap();
esp!(unsafe { rmt_driver_uninstall(C::channel()) }).unwrap();
} }
} }
unsafe impl<'d, C: RmtChannel> Send for RmtDriver<'d, C> {} impl<'d> Drop for RmtDriver<'d> {
/// Stop transmitting and release the driver.
fn drop(&mut self) {
self.stop().unwrap();
esp!(unsafe { rmt_driver_uninstall(self.channel()) }).unwrap();
}
}
unsafe impl<'d> Send for RmtDriver<'d> {}
/// Signal storage for [`Transmit`] in a format ready for the RMT driver. /// Signal storage for [`Transmit`] in a format ready for the RMT driver.
pub trait Signal { pub trait Signal {

View File

@ -30,7 +30,7 @@ use esp_idf_sys::*;
use crate::delay::BLOCK; use crate::delay::BLOCK;
use crate::gpio::{self, InputPin, OutputPin}; use crate::gpio::{self, InputPin, OutputPin};
use crate::peripheral::{Peripheral, PeripheralRef}; use crate::peripheral::Peripheral;
crate::embedded_hal_error!( crate::embedded_hal_error!(
SpiError, SpiError,
@ -299,13 +299,14 @@ impl<'d> SpiBus for SpiBusMasterDriver<'d> {
} }
/// Master SPI abstraction /// Master SPI abstraction
pub struct SpiMasterDriver<'d, SPI: Spi> { pub struct SpiMasterDriver<'d> {
_spi: PeripheralRef<'d, SPI>, host: u8,
device: spi_device_handle_t, device: spi_device_handle_t,
max_transfer_size: usize, max_transfer_size: usize,
_p: PhantomData<&'d ()>,
} }
impl<'d> SpiMasterDriver<'d, SPI1> { impl<'d> SpiMasterDriver<'d> {
/// Create new instance of SPI controller for SPI1 /// Create new instance of SPI controller for SPI1
/// ///
/// SPI1 can only use fixed pin for SCLK, SDO and SDI as they are shared with SPI0. /// SPI1 can only use fixed pin for SCLK, SDO and SDI as they are shared with SPI0.
@ -319,11 +320,9 @@ impl<'d> SpiMasterDriver<'d, SPI1> {
) -> Result<Self, EspError> { ) -> Result<Self, EspError> {
SpiMasterDriver::new_internal(spi, sclk, sdo, sdi, cs, config) SpiMasterDriver::new_internal(spi, sclk, sdo, sdi, cs, config)
} }
}
impl<'d, SPI: SpiAnyPins> SpiMasterDriver<'d, SPI> {
/// Create new instance of SPI controller for all others /// Create new instance of SPI controller for all others
pub fn new( pub fn new<SPI: SpiAnyPins>(
spi: impl Peripheral<P = SPI> + 'd, spi: impl Peripheral<P = SPI> + 'd,
sclk: impl Peripheral<P = impl OutputPin> + 'd, sclk: impl Peripheral<P = impl OutputPin> + 'd,
sdo: impl Peripheral<P = impl OutputPin> + 'd, sdo: impl Peripheral<P = impl OutputPin> + 'd,
@ -333,19 +332,17 @@ impl<'d, SPI: SpiAnyPins> SpiMasterDriver<'d, SPI> {
) -> Result<Self, EspError> { ) -> Result<Self, EspError> {
SpiMasterDriver::new_internal(spi, sclk, sdo, sdi, cs, config) SpiMasterDriver::new_internal(spi, sclk, sdo, sdi, cs, config)
} }
}
impl<'d, SPI: Spi> SpiMasterDriver<'d, SPI> {
/// Internal implementation of new shared by all SPI controllers /// Internal implementation of new shared by all SPI controllers
fn new_internal( fn new_internal<SPI: Spi>(
spi: impl Peripheral<P = SPI> + 'd, _spi: impl Peripheral<P = SPI> + 'd,
sclk: impl Peripheral<P = impl OutputPin> + 'd, sclk: impl Peripheral<P = impl OutputPin> + 'd,
sdo: impl Peripheral<P = impl OutputPin> + 'd, sdo: impl Peripheral<P = impl OutputPin> + 'd,
sdi: Option<impl Peripheral<P = impl InputPin + OutputPin> + 'd>, sdi: Option<impl Peripheral<P = impl InputPin + OutputPin> + 'd>,
cs: Option<impl Peripheral<P = impl OutputPin> + 'd>, cs: Option<impl Peripheral<P = impl OutputPin> + 'd>,
config: &config::Config, config: &config::Config,
) -> Result<Self, EspError> { ) -> Result<Self, EspError> {
crate::into_ref!(spi, sclk, sdo); crate::into_ref!(sclk, sdo);
let sdi = sdi.map(|sdi| sdi.into_ref()); let sdi = sdi.map(|sdi| sdi.into_ref());
let cs = cs.map(|cs| cs.into_ref()); let cs = cs.map(|cs| cs.into_ref());
@ -418,16 +415,21 @@ impl<'d, SPI: Spi> SpiMasterDriver<'d, SPI> {
})?; })?;
Ok(Self { Ok(Self {
_spi: spi, host: SPI::device() as _,
device: device_handle, device: device_handle,
max_transfer_size: config.dma.max_transfer_size(), max_transfer_size: config.dma.max_transfer_size(),
_p: PhantomData,
}) })
} }
pub fn device_handle(&mut self) -> spi_device_handle_t { pub fn device(&self) -> spi_device_handle_t {
self.device self.device
} }
pub fn host(&self) -> spi_host_device_t {
self.host as _
}
pub fn transaction<R, E>( pub fn transaction<R, E>(
&mut self, &mut self,
f: impl FnOnce(&mut SpiBusMasterDriver<'d>) -> Result<R, E>, f: impl FnOnce(&mut SpiBusMasterDriver<'d>) -> Result<R, E>,
@ -465,20 +467,20 @@ impl<'d, SPI: Spi> SpiMasterDriver<'d, SPI> {
} }
} }
impl<'d, SPI: Spi> Drop for SpiMasterDriver<'d, SPI> { impl<'d> Drop for SpiMasterDriver<'d> {
fn drop(&mut self) { fn drop(&mut self) {
esp!(unsafe { spi_bus_remove_device(self.device) }).unwrap(); esp!(unsafe { spi_bus_remove_device(self.device) }).unwrap();
esp!(unsafe { spi_bus_free(SPI::device()) }).unwrap(); esp!(unsafe { spi_bus_free(self.host()) }).unwrap();
} }
} }
unsafe impl<'d, SPI: Spi> Send for SpiMasterDriver<'d, SPI> {} unsafe impl<'d> Send for SpiMasterDriver<'d> {}
impl<'d, SPI: Spi> embedded_hal::spi::ErrorType for SpiMasterDriver<'d, SPI> { impl<'d> embedded_hal::spi::ErrorType for SpiMasterDriver<'d> {
type Error = SpiError; type Error = SpiError;
} }
impl<'d, SPI: Spi> SpiDevice for SpiMasterDriver<'d, SPI> { impl<'d> SpiDevice for SpiMasterDriver<'d> {
type Bus = SpiBusMasterDriver<'d>; type Bus = SpiBusMasterDriver<'d>;
fn transaction<R>( fn transaction<R>(
@ -489,7 +491,7 @@ impl<'d, SPI: Spi> SpiDevice for SpiMasterDriver<'d, SPI> {
} }
} }
impl<'d, SPI: Spi> embedded_hal_0_2::blocking::spi::Transfer<u8> for SpiMasterDriver<'d, SPI> { impl<'d> embedded_hal_0_2::blocking::spi::Transfer<u8> for SpiMasterDriver<'d> {
type Error = SpiError; type Error = SpiError;
fn transfer<'w>(&mut self, words: &'w mut [u8]) -> Result<&'w [u8], Self::Error> { fn transfer<'w>(&mut self, words: &'w mut [u8]) -> Result<&'w [u8], Self::Error> {
@ -506,7 +508,7 @@ impl<'d, SPI: Spi> embedded_hal_0_2::blocking::spi::Transfer<u8> for SpiMasterDr
} }
} }
impl<'d, SPI: Spi> embedded_hal_0_2::blocking::spi::Write<u8> for SpiMasterDriver<'d, SPI> { impl<'d> embedded_hal_0_2::blocking::spi::Write<u8> for SpiMasterDriver<'d> {
type Error = SpiError; type Error = SpiError;
fn write(&mut self, words: &[u8]) -> Result<(), Self::Error> { fn write(&mut self, words: &[u8]) -> Result<(), Self::Error> {
@ -528,7 +530,7 @@ impl<'d, SPI: Spi> embedded_hal_0_2::blocking::spi::Write<u8> for SpiMasterDrive
} }
} }
impl<'d, SPI: Spi> embedded_hal_0_2::blocking::spi::WriteIter<u8> for SpiMasterDriver<'d, SPI> { impl<'d> embedded_hal_0_2::blocking::spi::WriteIter<u8> for SpiMasterDriver<'d> {
type Error = SpiError; type Error = SpiError;
fn write_iter<WI>(&mut self, words: WI) -> Result<(), Self::Error> fn write_iter<WI>(&mut self, words: WI) -> Result<(), Self::Error>
@ -563,7 +565,7 @@ impl<'d, SPI: Spi> embedded_hal_0_2::blocking::spi::WriteIter<u8> for SpiMasterD
} }
} }
impl<'d, SPI: Spi> embedded_hal_0_2::blocking::spi::Transactional<u8> for SpiMasterDriver<'d, SPI> { impl<'d> embedded_hal_0_2::blocking::spi::Transactional<u8> for SpiMasterDriver<'d> {
type Error = SpiError; type Error = SpiError;
fn exec<'a>( fn exec<'a>(

View File

@ -1,6 +1,8 @@
use core::marker::PhantomData;
use esp_idf_sys::*; use esp_idf_sys::*;
use crate::peripheral::{Peripheral, PeripheralRef}; use crate::peripheral::Peripheral;
#[cfg(feature = "alloc")] #[cfg(feature = "alloc")]
extern crate alloc; extern crate alloc;
@ -54,23 +56,16 @@ pub trait Timer: Send {
fn index() -> timer_idx_t; fn index() -> timer_idx_t;
} }
pub struct TimerDriver<'d, TIMER> pub struct TimerDriver<'d> {
where timer: u8,
TIMER: Timer, _p: PhantomData<&'d ()>,
{
_timer: PeripheralRef<'d, TIMER>,
} }
impl<'d, TIMER> TimerDriver<'d, TIMER> impl<'d> TimerDriver<'d> {
where pub fn new<TIMER: Timer>(
TIMER: Timer, _timer: impl Peripheral<P = TIMER> + 'd,
{
pub fn new(
timer: impl Peripheral<P = TIMER> + 'd,
config: &config::Config, config: &config::Config,
) -> Result<TimerDriver<'d, TIMER>, EspError> { ) -> Result<Self, EspError> {
crate::into_ref!(timer);
esp!(unsafe { esp!(unsafe {
timer_init( timer_init(
TIMER::group(), TIMER::group(),
@ -94,16 +89,19 @@ where
) )
})?; })?;
Ok(TimerDriver { _timer: timer }) Ok(TimerDriver {
timer: ((TIMER::group() as u8) << 4) | (TIMER::index() as u8),
_p: PhantomData,
})
} }
pub fn enable(&mut self, enable: bool) -> Result<(), EspError> { pub fn enable(&mut self, enable: bool) -> Result<(), EspError> {
self.check(); self.check();
if enable { if enable {
esp!(unsafe { timer_start(TIMER::group(), TIMER::index()) })?; esp!(unsafe { timer_start(self.group(), self.index()) })?;
} else { } else {
esp!(unsafe { timer_pause(TIMER::group(), TIMER::index()) })?; esp!(unsafe { timer_pause(self.group(), self.index()) })?;
} }
Ok(()) Ok(())
@ -111,12 +109,12 @@ where
pub fn counter(&self) -> Result<u64, EspError> { pub fn counter(&self) -> Result<u64, EspError> {
let value = if crate::interrupt::active() { let value = if crate::interrupt::active() {
unsafe { timer_group_get_counter_value_in_isr(TIMER::group(), TIMER::index()) } unsafe { timer_group_get_counter_value_in_isr(self.group(), self.index()) }
} else { } else {
let mut value = 0_u64; let mut value = 0_u64;
esp!(unsafe { esp!(unsafe {
timer_get_counter_value(TIMER::group(), TIMER::index(), &mut value as *mut _) timer_get_counter_value(self.group(), self.index(), &mut value as *mut _)
})?; })?;
value value
@ -128,7 +126,7 @@ where
pub fn set_counter(&mut self, value: u64) -> Result<(), EspError> { pub fn set_counter(&mut self, value: u64) -> Result<(), EspError> {
self.check(); self.check();
esp!(unsafe { timer_set_counter_value(TIMER::group(), TIMER::index(), value) })?; esp!(unsafe { timer_set_counter_value(self.group(), self.index(), value) })?;
Ok(()) Ok(())
} }
@ -137,7 +135,7 @@ where
if crate::interrupt::active() { if crate::interrupt::active() {
if enable { if enable {
unsafe { unsafe {
timer_group_enable_alarm_in_isr(TIMER::group(), TIMER::index()); timer_group_enable_alarm_in_isr(self.group(), self.index());
} }
} else { } else {
panic!("Disabling alarm from an ISR is not supported"); panic!("Disabling alarm from an ISR is not supported");
@ -145,8 +143,8 @@ where
} else { } else {
esp!(unsafe { esp!(unsafe {
timer_set_alarm( timer_set_alarm(
TIMER::group(), self.group(),
TIMER::index(), self.index(),
if enable { if enable {
timer_alarm_t_TIMER_ALARM_EN timer_alarm_t_TIMER_ALARM_EN
} else { } else {
@ -164,7 +162,7 @@ where
let mut value = 0_u64; let mut value = 0_u64;
esp!(unsafe { timer_get_alarm_value(TIMER::group(), TIMER::index(), &mut value) })?; esp!(unsafe { timer_get_alarm_value(self.group(), self.index(), &mut value) })?;
Ok(value) Ok(value)
} }
@ -172,10 +170,10 @@ where
pub fn set_alarm(&mut self, value: u64) -> Result<(), EspError> { pub fn set_alarm(&mut self, value: u64) -> Result<(), EspError> {
if crate::interrupt::active() { if crate::interrupt::active() {
unsafe { unsafe {
timer_group_set_alarm_value_in_isr(TIMER::group(), TIMER::index(), value); timer_group_set_alarm_value_in_isr(self.group(), self.index(), value);
} }
} else { } else {
esp!(unsafe { timer_set_alarm_value(TIMER::group(), TIMER::index(), value) })?; esp!(unsafe { timer_set_alarm_value(self.group(), self.index(), value) })?;
} }
Ok(()) Ok(())
@ -184,7 +182,7 @@ where
pub fn enable_interrupt(&mut self) -> Result<(), EspError> { pub fn enable_interrupt(&mut self) -> Result<(), EspError> {
self.check(); self.check();
esp!(unsafe { timer_enable_intr(TIMER::group(), TIMER::index()) })?; esp!(unsafe { timer_enable_intr(self.group(), self.index()) })?;
Ok(()) Ok(())
} }
@ -192,7 +190,7 @@ where
pub fn disable_interrupt(&mut self) -> Result<(), EspError> { pub fn disable_interrupt(&mut self) -> Result<(), EspError> {
self.check(); self.check();
esp!(unsafe { timer_disable_intr(TIMER::group(), TIMER::index()) })?; esp!(unsafe { timer_disable_intr(self.group(), self.index()) })?;
Ok(()) Ok(())
} }
@ -209,16 +207,16 @@ where
let callback: Box<dyn FnMut() + 'static> = Box::new(callback); let callback: Box<dyn FnMut() + 'static> = Box::new(callback);
ISR_HANDLERS[(TIMER::group() * timer_group_t_TIMER_GROUP_MAX + TIMER::index()) as usize] = ISR_HANDLERS[(self.group() * timer_group_t_TIMER_GROUP_MAX + self.index()) as usize] =
Some(Box::new(callback)); Some(Box::new(callback));
esp!(timer_isr_callback_add( esp!(timer_isr_callback_add(
TIMER::group(), self.group(),
TIMER::index(), self.index(),
Some(Self::handle_isr), Some(Self::handle_isr),
UnsafeCallback::from( UnsafeCallback::from(
ISR_HANDLERS ISR_HANDLERS
[(TIMER::group() * timer_group_t_TIMER_GROUP_MAX + TIMER::index()) as usize] [(self.group() * timer_group_t_TIMER_GROUP_MAX + self.index()) as usize]
.as_mut() .as_mut()
.unwrap(), .unwrap(),
) )
@ -237,16 +235,15 @@ where
unsafe { unsafe {
let subscribed = ISR_HANDLERS let subscribed = ISR_HANDLERS
[(TIMER::group() * timer_group_t_TIMER_GROUP_MAX + TIMER::index()) as usize] [(self.group() * timer_group_t_TIMER_GROUP_MAX + self.index()) as usize]
.is_some(); .is_some();
if subscribed { if subscribed {
esp!(timer_disable_intr(TIMER::group(), TIMER::index()))?; esp!(timer_disable_intr(self.group(), self.index()))?;
esp!(timer_isr_callback_remove(TIMER::group(), TIMER::index()))?; esp!(timer_isr_callback_remove(self.group(), self.index()))?;
ISR_HANDLERS ISR_HANDLERS
[(TIMER::group() * timer_group_t_TIMER_GROUP_MAX + TIMER::index()) as usize] = [(self.group() * timer_group_t_TIMER_GROUP_MAX + self.index()) as usize] = None;
None;
} }
} }
@ -265,20 +262,28 @@ where
UnsafeCallback::from_ptr(unsafe_callback).call(); UnsafeCallback::from_ptr(unsafe_callback).call();
}) })
} }
pub fn group(&self) -> timer_group_t {
(self.timer >> 4) as _
}
pub fn index(&self) -> timer_idx_t {
(self.timer & 0xf) as _
}
} }
impl<'d, TIMER: Timer> Drop for TimerDriver<'d, TIMER> { impl<'d> Drop for TimerDriver<'d> {
fn drop(&mut self) { fn drop(&mut self) {
#[cfg(feature = "alloc")] #[cfg(feature = "alloc")]
{ {
self.unsubscribe().unwrap(); self.unsubscribe().unwrap();
} }
esp!(unsafe { timer_deinit(TIMER::group(), TIMER::index()) }).unwrap(); esp!(unsafe { timer_deinit(self.group(), self.index()) }).unwrap();
} }
} }
unsafe impl<'d, TIMER: Timer> Send for TimerDriver<'d, TIMER> {} unsafe impl<'d> Send for TimerDriver<'d> {}
#[cfg(feature = "alloc")] #[cfg(feature = "alloc")]
struct UnsafeCallback(*mut Box<dyn FnMut() + 'static>); struct UnsafeCallback(*mut Box<dyn FnMut() + 'static>);

View File

@ -46,7 +46,7 @@ use crate::units::*;
use esp_idf_sys::*; use esp_idf_sys::*;
use crate::peripheral::{Peripheral, PeripheralRef}; use crate::peripheral::Peripheral;
const UART_FIFO_SIZE: i32 = 128; const UART_FIFO_SIZE: i32 = 128;
@ -283,33 +283,34 @@ crate::embedded_hal_error!(
/// Serial abstraction /// Serial abstraction
/// ///
pub struct UartDriver<'d, UART: Uart> { pub struct UartDriver<'d> {
_uart: PeripheralRef<'d, UART>, port: u8,
rx: UartRxDriver<'d, UART>, _p: PhantomData<&'d ()>,
tx: UartTxDriver<'d, UART>,
} }
/// Serial receiver /// Serial receiver
pub struct UartRxDriver<'d, UART: Uart> { pub struct UartRxDriver<'d> {
_uart: PhantomData<&'d UART>, port: u8,
_p: PhantomData<&'d ()>,
} }
/// Serial transmitter /// Serial transmitter
pub struct UartTxDriver<'d, UART: Uart> { pub struct UartTxDriver<'d> {
_uart: PhantomData<&'d UART>, port: u8,
_p: PhantomData<&'d ()>,
} }
impl<'d, UART: Uart> UartDriver<'d, UART> { impl<'d> UartDriver<'d> {
/// Create a new serial driver /// Create a new serial driver
pub fn new( pub fn new<UART: Uart>(
uart: impl Peripheral<P = UART> + 'd, _uart: impl Peripheral<P = UART> + 'd,
tx: impl Peripheral<P = impl OutputPin> + 'd, tx: impl Peripheral<P = impl OutputPin> + 'd,
rx: impl Peripheral<P = impl InputPin> + 'd, rx: impl Peripheral<P = impl InputPin> + 'd,
cts: Option<impl Peripheral<P = impl InputPin> + 'd>, cts: Option<impl Peripheral<P = impl InputPin> + 'd>,
rts: Option<impl Peripheral<P = impl OutputPin> + 'd>, rts: Option<impl Peripheral<P = impl OutputPin> + 'd>,
config: &config::Config, config: &config::Config,
) -> Result<Self, EspError> { ) -> Result<Self, EspError> {
crate::into_ref!(uart, tx, rx); crate::into_ref!(tx, rx);
let cts = cts.map(|cts| cts.into_ref()); let cts = cts.map(|cts| cts.into_ref());
let rts = rts.map(|rts| rts.into_ref()); let rts = rts.map(|rts| rts.into_ref());
@ -348,16 +349,15 @@ impl<'d, UART: Uart> UartDriver<'d, UART> {
})?; })?;
Ok(Self { Ok(Self {
_uart: uart, port: UART::port() as _,
rx: UartRxDriver { _uart: PhantomData }, _p: PhantomData,
tx: UartTxDriver { _uart: PhantomData },
}) })
} }
/// Change the number of stop bits /// Change the number of stop bits
pub fn change_stop_bits(&mut self, stop_bits: config::StopBits) -> Result<&mut Self, EspError> { pub fn change_stop_bits(&mut self, stop_bits: config::StopBits) -> Result<&mut Self, EspError> {
esp_result!( esp_result!(
unsafe { uart_set_stop_bits(UART::port(), stop_bits.into()) }, unsafe { uart_set_stop_bits(self.port(), stop_bits.into()) },
self self
) )
} }
@ -366,7 +366,7 @@ impl<'d, UART: Uart> UartDriver<'d, UART> {
pub fn stop_bits(&self) -> Result<config::StopBits, EspError> { pub fn stop_bits(&self) -> Result<config::StopBits, EspError> {
let mut stop_bits: uart_stop_bits_t = 0; let mut stop_bits: uart_stop_bits_t = 0;
esp_result!( esp_result!(
unsafe { uart_get_stop_bits(UART::port(), &mut stop_bits) }, unsafe { uart_get_stop_bits(self.port(), &mut stop_bits) },
stop_bits.into() stop_bits.into()
) )
} }
@ -374,7 +374,7 @@ impl<'d, UART: Uart> UartDriver<'d, UART> {
/// Change the number of data bits /// Change the number of data bits
pub fn change_data_bits(&mut self, data_bits: config::DataBits) -> Result<&mut Self, EspError> { pub fn change_data_bits(&mut self, data_bits: config::DataBits) -> Result<&mut Self, EspError> {
esp_result!( esp_result!(
unsafe { uart_set_word_length(UART::port(), data_bits.into()) }, unsafe { uart_set_word_length(self.port(), data_bits.into()) },
self self
) )
} }
@ -383,24 +383,21 @@ impl<'d, UART: Uart> UartDriver<'d, UART> {
pub fn data_bits(&self) -> Result<config::DataBits, EspError> { pub fn data_bits(&self) -> Result<config::DataBits, EspError> {
let mut data_bits: uart_word_length_t = 0; let mut data_bits: uart_word_length_t = 0;
esp_result!( esp_result!(
unsafe { uart_get_word_length(UART::port(), &mut data_bits) }, unsafe { uart_get_word_length(self.port(), &mut data_bits) },
data_bits.into() data_bits.into()
) )
} }
/// Change the type of parity checking /// Change the type of parity checking
pub fn change_parity(&mut self, parity: config::Parity) -> Result<&mut Self, EspError> { pub fn change_parity(&mut self, parity: config::Parity) -> Result<&mut Self, EspError> {
esp_result!( esp_result!(unsafe { uart_set_parity(self.port(), parity.into()) }, self)
unsafe { uart_set_parity(UART::port(), parity.into()) },
self
)
} }
/// Returns the current type of parity checking /// Returns the current type of parity checking
pub fn parity(&self) -> Result<config::Parity, EspError> { pub fn parity(&self) -> Result<config::Parity, EspError> {
let mut parity: uart_parity_t = 0; let mut parity: uart_parity_t = 0;
esp_result!( esp_result!(
unsafe { uart_get_parity(UART::port(), &mut parity) }, unsafe { uart_get_parity(self.port(), &mut parity) },
parity.into() parity.into()
) )
} }
@ -417,7 +414,7 @@ impl<'d, UART: Uart> UartDriver<'d, UART> {
baudrate: T, baudrate: T,
) -> Result<&mut Self, EspError> { ) -> Result<&mut Self, EspError> {
esp_result!( esp_result!(
unsafe { uart_set_baudrate(UART::port(), baudrate.into().into()) }, unsafe { uart_set_baudrate(self.port(), baudrate.into().into()) },
self self
) )
} }
@ -426,99 +423,117 @@ impl<'d, UART: Uart> UartDriver<'d, UART> {
pub fn baudrate(&self) -> Result<Hertz, EspError> { pub fn baudrate(&self) -> Result<Hertz, EspError> {
let mut baudrate: u32 = 0; let mut baudrate: u32 = 0;
esp_result!( esp_result!(
unsafe { uart_get_baudrate(UART::port(), &mut baudrate) }, unsafe { uart_get_baudrate(self.port(), &mut baudrate) },
baudrate.into() baudrate.into()
) )
} }
/// Split the serial driver in separate TX and RX drivers /// Split the serial driver in separate TX and RX drivers
pub fn split(&mut self) -> (&mut UartTxDriver<'d, UART>, &mut UartRxDriver<'d, UART>) { pub fn split(mut self) -> (UartTxDriver<'d>, UartRxDriver<'d>) {
(&mut self.tx, &mut self.rx) (self.tx(), self.rx())
} }
/// Read multiple bytes into a slice /// Read multiple bytes into a slice
pub fn read(&mut self, buf: &mut [u8], delay: TickType_t) -> Result<usize, EspError> { pub fn read(&mut self, buf: &mut [u8], delay: TickType_t) -> Result<usize, EspError> {
self.rx.read(buf, delay) self.rx().read(buf, delay)
} }
/// Write multiple bytes from a slice /// Write multiple bytes from a slice
pub fn write(&mut self, buf: &[u8]) -> Result<usize, EspError> { pub fn write(&mut self, buf: &[u8]) -> Result<usize, EspError> {
self.tx.write(buf) self.tx().write(buf)
} }
pub fn flush_read(&mut self) -> Result<(), EspError> { pub fn flush_read(&mut self) -> Result<(), EspError> {
self.rx.flush() self.rx().flush()
} }
pub fn flush_write(&mut self) -> Result<(), EspError> { pub fn flush_write(&mut self) -> Result<(), EspError> {
self.tx.flush() self.tx().flush()
}
pub fn port(&self) -> uart_port_t {
self.port as _
}
fn rx(&mut self) -> UartRxDriver<'d> {
UartRxDriver {
port: self.port() as _,
_p: PhantomData,
}
}
fn tx(&mut self) -> UartTxDriver<'d> {
UartTxDriver {
port: self.port() as _,
_p: PhantomData,
}
} }
} }
impl<'d, UART: Uart> Drop for UartDriver<'d, UART> { impl<'d> Drop for UartDriver<'d> {
fn drop(&mut self) { fn drop(&mut self) {
esp!(unsafe { uart_driver_delete(UART::port()) }).unwrap(); esp!(unsafe { uart_driver_delete(self.port()) }).unwrap();
} }
} }
unsafe impl<'d, UART: Uart> Send for UartDriver<'d, UART> {} unsafe impl<'d> Send for UartDriver<'d> {}
impl<'d, UART: Uart> embedded_hal::serial::ErrorType for UartDriver<'d, UART> { impl<'d> embedded_hal::serial::ErrorType for UartDriver<'d> {
type Error = SerialError; type Error = SerialError;
} }
impl<'d, UART: Uart> embedded_hal_0_2::serial::Read<u8> for UartDriver<'d, UART> { impl<'d> embedded_hal_0_2::serial::Read<u8> for UartDriver<'d> {
type Error = SerialError; type Error = SerialError;
fn read(&mut self) -> nb::Result<u8, Self::Error> { fn read(&mut self) -> nb::Result<u8, Self::Error> {
embedded_hal_0_2::serial::Read::read(&mut self.rx) embedded_hal_0_2::serial::Read::read(&mut self.rx())
} }
} }
impl<'d, UART: Uart> embedded_hal_nb::serial::Read<u8> for UartDriver<'d, UART> { impl<'d> embedded_hal_nb::serial::Read<u8> for UartDriver<'d> {
fn read(&mut self) -> nb::Result<u8, Self::Error> { fn read(&mut self) -> nb::Result<u8, Self::Error> {
embedded_hal_nb::serial::Read::read(&mut self.rx) embedded_hal_nb::serial::Read::read(&mut self.rx())
} }
} }
impl<'d, UART: Uart> embedded_hal_0_2::serial::Write<u8> for UartDriver<'d, UART> { impl<'d> embedded_hal_0_2::serial::Write<u8> for UartDriver<'d> {
type Error = SerialError; type Error = SerialError;
fn flush(&mut self) -> nb::Result<(), Self::Error> { fn flush(&mut self) -> nb::Result<(), Self::Error> {
embedded_hal_0_2::serial::Write::flush(&mut self.tx) embedded_hal_0_2::serial::Write::flush(&mut self.tx())
} }
fn write(&mut self, byte: u8) -> nb::Result<(), Self::Error> { fn write(&mut self, byte: u8) -> nb::Result<(), Self::Error> {
embedded_hal_0_2::serial::Write::write(&mut self.tx, byte) embedded_hal_0_2::serial::Write::write(&mut self.tx(), byte)
} }
} }
impl<'d, UART: Uart> embedded_hal_nb::serial::Write<u8> for UartDriver<'d, UART> { impl<'d> embedded_hal_nb::serial::Write<u8> for UartDriver<'d> {
fn flush(&mut self) -> nb::Result<(), Self::Error> { fn flush(&mut self) -> nb::Result<(), Self::Error> {
embedded_hal_nb::serial::Write::flush(&mut self.tx) embedded_hal_nb::serial::Write::flush(&mut self.tx())
} }
fn write(&mut self, byte: u8) -> nb::Result<(), Self::Error> { fn write(&mut self, byte: u8) -> nb::Result<(), Self::Error> {
embedded_hal_nb::serial::Write::write(&mut self.tx, byte) embedded_hal_nb::serial::Write::write(&mut self.tx(), byte)
} }
} }
impl<'d, UART: Uart> core::fmt::Write for UartDriver<'d, UART> { impl<'d> core::fmt::Write for UartDriver<'d> {
fn write_str(&mut self, s: &str) -> core::fmt::Result { fn write_str(&mut self, s: &str) -> core::fmt::Result {
self.tx.write_str(s) self.tx().write_str(s)
} }
} }
impl<'d, UART: Uart> embedded_hal::serial::ErrorType for UartRxDriver<'d, UART> { impl<'d> embedded_hal::serial::ErrorType for UartRxDriver<'d> {
type Error = SerialError; type Error = SerialError;
} }
impl<'d, UART: Uart> UartRxDriver<'d, UART> { impl<'d> UartRxDriver<'d> {
/// Get count of bytes in the receive FIFO /// Get count of bytes in the receive FIFO
pub fn count(&self) -> Result<u8, EspError> { pub fn count(&self) -> Result<u8, EspError> {
let mut size = 0_u32; let mut size = 0_u32;
esp_result!( esp_result!(
unsafe { uart_get_buffered_data_len(UART::port(), &mut size) }, unsafe { uart_get_buffered_data_len(self.port(), &mut size) },
size as u8 size as u8
) )
} }
@ -529,7 +544,7 @@ impl<'d, UART: Uart> UartRxDriver<'d, UART> {
// 0 means timeout and nothing is yet read out // 0 means timeout and nothing is yet read out
let len = unsafe { let len = unsafe {
uart_read_bytes( uart_read_bytes(
UART::port(), self.port(),
buf.as_mut_ptr() as *mut _, buf.as_mut_ptr() as *mut _,
buf.len() as u32, buf.len() as u32,
delay, delay,
@ -544,13 +559,17 @@ impl<'d, UART: Uart> UartRxDriver<'d, UART> {
} }
pub fn flush(&self) -> Result<(), EspError> { pub fn flush(&self) -> Result<(), EspError> {
esp!(unsafe { uart_flush_input(UART::port()) })?; esp!(unsafe { uart_flush_input(self.port()) })?;
Ok(()) Ok(())
} }
pub fn port(&self) -> uart_port_t {
self.port as _
}
} }
impl<'d, UART: Uart> embedded_hal_0_2::serial::Read<u8> for UartRxDriver<'d, UART> { impl<'d> embedded_hal_0_2::serial::Read<u8> for UartRxDriver<'d> {
type Error = SerialError; type Error = SerialError;
fn read(&mut self) -> nb::Result<u8, Self::Error> { fn read(&mut self) -> nb::Result<u8, Self::Error> {
@ -562,7 +581,7 @@ impl<'d, UART: Uart> embedded_hal_0_2::serial::Read<u8> for UartRxDriver<'d, UAR
} }
} }
impl<'d, UART: Uart> embedded_hal_nb::serial::Read<u8> for UartRxDriver<'d, UART> { impl<'d> embedded_hal_nb::serial::Read<u8> for UartRxDriver<'d> {
fn read(&mut self) -> nb::Result<u8, Self::Error> { fn read(&mut self) -> nb::Result<u8, Self::Error> {
let mut buf = [0_u8]; let mut buf = [0_u8];
@ -572,12 +591,12 @@ impl<'d, UART: Uart> embedded_hal_nb::serial::Read<u8> for UartRxDriver<'d, UART
} }
} }
impl<'d, UART: Uart> UartTxDriver<'d, UART> { impl<'d> UartTxDriver<'d> {
/// Write multiple bytes from a slice /// Write multiple bytes from a slice
pub fn write(&mut self, bytes: &[u8]) -> Result<usize, EspError> { pub fn write(&mut self, bytes: &[u8]) -> Result<usize, EspError> {
// `uart_write_bytes()` returns error (-1) or how many bytes were written // `uart_write_bytes()` returns error (-1) or how many bytes were written
let len = unsafe { let len = unsafe {
uart_write_bytes(UART::port(), bytes.as_ptr() as *const _, bytes.len() as u32) uart_write_bytes(self.port(), bytes.as_ptr() as *const _, bytes.len() as u32)
}; };
if len >= 0 { if len >= 0 {
@ -588,17 +607,21 @@ impl<'d, UART: Uart> UartTxDriver<'d, UART> {
} }
pub fn flush(&mut self) -> Result<(), EspError> { pub fn flush(&mut self) -> Result<(), EspError> {
esp!(unsafe { uart_wait_tx_done(UART::port(), 0) })?; esp!(unsafe { uart_wait_tx_done(self.port(), 0) })?;
Ok(()) Ok(())
} }
pub fn port(&self) -> uart_port_t {
self.port as _
}
} }
impl<'d, UART: Uart> embedded_hal::serial::ErrorType for UartTxDriver<'d, UART> { impl<'d> embedded_hal::serial::ErrorType for UartTxDriver<'d> {
type Error = SerialError; type Error = SerialError;
} }
impl<'d, UART: Uart> embedded_hal_0_2::serial::Write<u8> for UartTxDriver<'d, UART> { impl<'d> embedded_hal_0_2::serial::Write<u8> for UartTxDriver<'d> {
type Error = SerialError; type Error = SerialError;
fn flush(&mut self) -> nb::Result<(), Self::Error> { fn flush(&mut self) -> nb::Result<(), Self::Error> {
@ -610,7 +633,7 @@ impl<'d, UART: Uart> embedded_hal_0_2::serial::Write<u8> for UartTxDriver<'d, UA
} }
} }
impl<'d, UART: Uart> embedded_hal_nb::serial::Write<u8> for UartTxDriver<'d, UART> { impl<'d> embedded_hal_nb::serial::Write<u8> for UartTxDriver<'d> {
fn flush(&mut self) -> nb::Result<(), Self::Error> { fn flush(&mut self) -> nb::Result<(), Self::Error> {
UartTxDriver::flush(self).map_err(to_nb_err) UartTxDriver::flush(self).map_err(to_nb_err)
} }
@ -620,7 +643,7 @@ impl<'d, UART: Uart> embedded_hal_nb::serial::Write<u8> for UartTxDriver<'d, UAR
} }
} }
impl<'d, UART: Uart> core::fmt::Write for UartTxDriver<'d, UART> { impl<'d> core::fmt::Write for UartTxDriver<'d> {
fn write_str(&mut self, s: &str) -> core::fmt::Result { fn write_str(&mut self, s: &str) -> core::fmt::Result {
let buf = s.as_bytes(); let buf = s.as_bytes();
let mut offset = 0; let mut offset = 0;