diff --git a/Cargo.toml b/Cargo.toml index cb5d3e2..ff1ec35 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -15,30 +15,29 @@ version = "0.6.0" features = ["stm32f746", "rt"] [dependencies] -as-slice = "0.1.0" +as-slice = "0.2.1" cortex-m = "0.7" cortex-m-rt = ">=0.6.15, <0.8" embedded-time = "0.12.0" -nb = "0.1.2" +nb = "1.0.0" rtcc = "0.2" stm32f7 = "0.14.0" -micromath = "1.0.0" +micromath = "2.0.0" synopsys-usb-otg = { version = "0.2.3", features = ["cortex-m"], optional = true } stm32-fmc = { version = "0.2.0", features = ["sdram"], optional = true } rand_core = "0.6" bxcan = "0.6" + [dependencies.bare-metal] -version = "0.2.4" -features = ["const-fn"] +version = "1.0.0" [dependencies.cast] default-features = false -version = "0.2.2" +version = "0.3.0" [dependencies.embedded-hal] -features = ["unproven"] -version = "0.2.3" +version = "1.0.0-alpha.6" [dependencies.void] default-features = false @@ -52,7 +51,7 @@ version = "0.4.1" cortex-m-semihosting = "0.3.3" panic-halt = "0.2.0" panic-semihosting = "0.5.2" -embedded-graphics = "0.6.1" +embedded-graphics = "0.6.2" usb-device = "0.2.5" usbd-serial = "0.1.0" diff --git a/examples/blinky_delay.rs b/examples/blinky_delay.rs index e091570..b10e40f 100644 --- a/examples/blinky_delay.rs +++ b/examples/blinky_delay.rs @@ -8,6 +8,7 @@ extern crate panic_halt; use cortex_m_rt::entry; +use embedded_hal::delay::blocking::DelayUs; use stm32f7xx_hal::{delay::Delay, pac, prelude::*}; #[entry] @@ -29,9 +30,9 @@ fn main() -> ! { loop { led.set_high(); - delay.delay_ms(500_u16); + delay.delay_ms(500).unwrap(); led.set_low(); - delay.delay_ms(500_u16); + delay.delay_ms(500).unwrap(); } } diff --git a/examples/i2c_scanner.rs b/examples/i2c_scanner.rs index f9e1566..212f988 100644 --- a/examples/i2c_scanner.rs +++ b/examples/i2c_scanner.rs @@ -11,6 +11,7 @@ use panic_semihosting as _; use cortex_m_rt::entry; use cortex_m_semihosting::{hprint, hprintln}; +use embedded_hal::i2c::blocking::Write; use stm32f7xx_hal::{self as hal, gpio::GpioExt, pac, prelude::*}; const VALID_ADDR_RANGE: Range = 0x08..0x78; diff --git a/examples/serial_delay.rs b/examples/serial_delay.rs index 0c1ff94..51c0634 100644 --- a/examples/serial_delay.rs +++ b/examples/serial_delay.rs @@ -12,6 +12,7 @@ extern crate panic_halt; use core::fmt::Write; use cortex_m_rt::entry; +use embedded_hal::delay::blocking::DelayUs; use stm32f7xx_hal::{ delay::Delay, pac, @@ -50,6 +51,6 @@ fn main() -> ! { let hello: &str = "Hello, I'm a STM32F7xx!\r\n"; loop { tx.write_str(hello).unwrap(); - delay.delay_ms(500_u16); + delay.delay_ms(500).unwrap(); } } diff --git a/examples/serial_echo.rs b/examples/serial_echo.rs index ddae8fa..91de7f4 100644 --- a/examples/serial_echo.rs +++ b/examples/serial_echo.rs @@ -12,6 +12,7 @@ extern crate panic_halt; use nb::block; use cortex_m_rt::entry; +use embedded_hal::serial::nb::{Read, Write}; use stm32f7xx_hal::{ pac, prelude::*, diff --git a/examples/spi.rs b/examples/spi.rs index c58db95..59c9438 100644 --- a/examples/spi.rs +++ b/examples/spi.rs @@ -4,6 +4,7 @@ extern crate panic_semihosting; use cortex_m_rt::entry; +use embedded_hal::spi::blocking::TransferInplace; use stm32f7xx_hal::{ pac, prelude::*, @@ -48,7 +49,7 @@ fn main() -> ! { let mut buffer = [0; 2]; buffer[0] = 0x75 | 0x80; ncs.set_low(); - spi.transfer(&mut buffer).unwrap(); + spi.transfer_inplace(&mut buffer).unwrap(); ncs.set_high(); // The WHO_AM_I register should always return 0x71. diff --git a/examples/spi_16.rs b/examples/spi_16.rs index 3f5c5a1..e8250ab 100644 --- a/examples/spi_16.rs +++ b/examples/spi_16.rs @@ -4,6 +4,7 @@ extern crate panic_semihosting; use cortex_m_rt::entry; +use embedded_hal::spi::blocking::Write; use stm32f7xx_hal::{ pac, prelude::*, diff --git a/examples/timer.rs b/examples/timer.rs index 10677f0..486950d 100644 --- a/examples/timer.rs +++ b/examples/timer.rs @@ -32,7 +32,7 @@ fn main() -> ! { unsafe { NVIC::unmask(pac::Interrupt::TIM2); } - let mut timer = Timer::tim2(dp.TIM2, 1.Hz(), clocks, &mut rcc.apb1); + let mut timer = Timer::tim2(dp.TIM2, 1.Hz(), clocks, &mut rcc.apb1).unwrap(); timer.listen(Event::TimeOut); loop {} diff --git a/src/adc.rs b/src/adc.rs index b2dec93..921a31f 100644 --- a/src/adc.rs +++ b/src/adc.rs @@ -11,7 +11,7 @@ use crate::pac::{ADC1, ADC2, ADC3, ADC_COMMON}; use cortex_m::asm::delay; -use embedded_hal::adc::{Channel, OneShot}; +use embedded_hal::adc::nb::{Channel, OneShot}; #[derive(Clone, Copy, Debug, PartialEq)] #[allow(non_camel_case_types)] @@ -95,7 +95,7 @@ macro_rules! adc_pins { impl Channel<$ADC> for $pin { type ID = u8; - fn channel() -> u8 { $chan } + fn channel(&self) -> u8 { $chan } } )+ }; @@ -442,8 +442,8 @@ macro_rules! adc_hal { { type Error = (); - fn read(&mut self, _pin: &mut PIN) -> nb::Result { - let res = self.convert(PIN::channel()); + fn read(&mut self, pin: &mut PIN) -> nb::Result { + let res = self.convert(PIN::channel(pin)); Ok(res.into()) } } diff --git a/src/delay.rs b/src/delay.rs index d01f80f..d0c1a93 100644 --- a/src/delay.rs +++ b/src/delay.rs @@ -1,10 +1,9 @@ //! Delays -use cast::u32; use cortex_m::peripheral::syst::SystClkSource; use cortex_m::peripheral::SYST; -use crate::hal::blocking::delay::{DelayMs, DelayUs}; +use crate::hal::delay::blocking::DelayUs; use crate::rcc::Clocks; /// System timer (SysTick) as a delay provider @@ -27,26 +26,10 @@ impl Delay { } } -impl DelayMs for Delay { - fn delay_ms(&mut self, ms: u32) { - self.delay_us(ms * 1_000); - } -} - -impl DelayMs for Delay { - fn delay_ms(&mut self, ms: u16) { - self.delay_ms(u32(ms)); - } -} - -impl DelayMs for Delay { - fn delay_ms(&mut self, ms: u8) { - self.delay_ms(u32(ms)); - } -} +impl DelayUs for Delay { + type Error = (); -impl DelayUs for Delay { - fn delay_us(&mut self, us: u32) { + fn delay_us(&mut self, us: u32) -> Result<(), Self::Error> { // The SysTick Reload Value register supports values between 1 and 0x00FFFFFF. const MAX_RVR: u32 = 0x00FF_FFFF; @@ -70,17 +53,6 @@ impl DelayUs for Delay { self.syst.disable_counter(); } - } -} - -impl DelayUs for Delay { - fn delay_us(&mut self, us: u16) { - self.delay_us(u32(us)) - } -} - -impl DelayUs for Delay { - fn delay_us(&mut self, us: u8) { - self.delay_us(u32(us)) + Ok(()) } } diff --git a/src/gpio.rs b/src/gpio.rs index f107dff..e2e45bb 100644 --- a/src/gpio.rs +++ b/src/gpio.rs @@ -47,10 +47,10 @@ use core::convert::Infallible; use core::marker::PhantomData; -pub use embedded_hal::digital::v2::PinState; -use embedded_hal::digital::v2::{ +use embedded_hal::digital::blocking::{ InputPin, IoPin, OutputPin, StatefulOutputPin, ToggleableOutputPin, }; +pub use embedded_hal::digital::PinState; use crate::pac::{EXTI, SYSCFG}; use crate::rcc::{Enable, APB2}; @@ -450,7 +450,7 @@ impl Pin, P, N> { #[inline(always)] pub fn toggle(&mut self) { - if self.is_set_low() { + if self.is_set_low().unwrap() { self.set_high() } else { self.set_low() diff --git a/src/gpio/erased.rs b/src/gpio/erased.rs index f6416c6..79b97af 100644 --- a/src/gpio/erased.rs +++ b/src/gpio/erased.rs @@ -99,7 +99,7 @@ impl ErasedPin> { #[inline(always)] pub fn toggle(&mut self) { - if self.is_set_low() { + if self.is_set_low().unwrap() { self.set_high() } else { self.set_low() diff --git a/src/gpio/partially_erased.rs b/src/gpio/partially_erased.rs index 79f344c..e9f6614 100644 --- a/src/gpio/partially_erased.rs +++ b/src/gpio/partially_erased.rs @@ -80,7 +80,7 @@ impl PartiallyErasedPin, P> { #[inline(always)] pub fn toggle(&mut self) { - if self.is_set_low() { + if self.is_set_low().unwrap() { self.set_high() } else { self.set_low() diff --git a/src/i2c.rs b/src/i2c.rs index 97baa18..2957263 100644 --- a/src/i2c.rs +++ b/src/i2c.rs @@ -10,11 +10,13 @@ use crate::gpio::gpioc::PC9; use crate::gpio::gpiof::{PF0, PF1}; use crate::gpio::gpioh::{PH4, PH5, PH7, PH8}; use crate::gpio::AlternateOD; -use crate::hal::blocking::i2c::{Read, Write, WriteRead}; +use crate::hal::i2c::{ + self, + blocking::{Read, Write, WriteRead}, +}; use crate::pac::{DWT, I2C1, I2C2, I2C3}; use crate::rcc::{Clocks, Enable, GetBusFreq, RccBus, Reset}; -use nb::Error::{Other, WouldBlock}; -use nb::{Error as NbError, Result as NbResult}; +use nb; use cast::u16; @@ -22,21 +24,36 @@ use cast::u16; #[derive(Debug, Eq, PartialEq)] #[non_exhaustive] pub enum Error { - /// Bus error + /// Bus error occurred. e.g. A START or a STOP condition is detected and is not + /// located after a multiple of 9 SCL clock pulses. Bus, - /// Arbitration loss - Arbitration, - /// No ack received - Acknowledge, - /// Overrun/underrun + /// The arbitration was lost, e.g. electrical problems with the clock signal + ArbitrationLoss, + /// A bus operation was not acknowledged, e.g. due to the addressed device not + /// being available on the bus or the device not being ready to process requests + /// at the moment + NoAcknowledge(i2c::NoAcknowledgeSource), + /// The peripheral receive buffer was overrun Overrun, - /// Bus is busy - Busy, + /// Timeout + Timeout, // Pec, // SMBUS mode only // Timeout, // SMBUS mode only // Alert, // SMBUS mode only } +impl i2c::Error for Error { + fn kind(&self) -> i2c::ErrorKind { + match *self { + Error::Bus => i2c::ErrorKind::Bus, + Error::ArbitrationLoss => i2c::ErrorKind::ArbitrationLoss, + Error::NoAcknowledge(s) => i2c::ErrorKind::NoAcknowledge(s), + Error::Overrun => i2c::ErrorKind::Overrun, + _ => i2c::ErrorKind::Other, + } + } +} + /// SPI mode. The user should make sure that the requested frequency can be /// generated considering the buses clocks. #[derive(Debug, PartialEq)] @@ -354,20 +371,22 @@ macro_rules! check_status_flag { if isr.berr().bit_is_set() { $i2c.icr.write(|w| w.berrcf().set_bit()); - Err(Other(Error::Bus)) + Err(nb::Error::Other(Error::Bus)) } else if isr.arlo().bit_is_set() { $i2c.icr.write(|w| w.arlocf().set_bit()); - Err(Other(Error::Arbitration)) + Err(nb::Error::Other(Error::ArbitrationLoss)) } else if isr.nackf().bit_is_set() { $i2c.icr.write(|w| w.stopcf().set_bit().nackcf().set_bit()); - Err(Other(Error::Acknowledge)) + Err(nb::Error::Other(Error::NoAcknowledge( + i2c::NoAcknowledgeSource::Unknown, + ))) } else if isr.ovr().bit_is_set() { $i2c.icr.write(|w| w.stopcf().set_bit().ovrcf().set_bit()); - Err(Other(Error::Overrun)) + Err(nb::Error::Other(Error::Overrun)) } else if isr.$flag().$status() { Ok(()) } else { - Err(WouldBlock) + Err(nb::Error::WouldBlock) } }}; } @@ -376,7 +395,7 @@ macro_rules! busy_wait { ($nb_expr:expr, $exit_cond:expr) => {{ loop { let res = $nb_expr; - if res != Err(WouldBlock) { + if res != Err(nb::Error::WouldBlock) { break res; } if $exit_cond { @@ -397,6 +416,17 @@ macro_rules! busy_wait_cycles { }}; } +// Map non-blocking errors to blocking errors +macro_rules! nbError_to_Error { + ($nb_expr:expr) => {{ + match $nb_expr { + Ok(()) => {} + Err(nb::Error::WouldBlock) => return Err(Error::Timeout), + Err(nb::Error::Other(error)) => return Err(error), + }; + }}; +} + // Generate the same code for both I2Cs macro_rules! hal { ($($I2CX:ident: ($i2cX:ident),)+) => { @@ -531,25 +561,19 @@ macro_rules! hal { /// Wait for a byte to be read and return it (ie for RXNE flag /// to be set) - fn wait_byte_read(&self) -> NbResult { + fn wait_byte_read(&self) -> Result { // Wait until we have received something - busy_wait_cycles!( - check_status_flag!(self.nb.i2c, rxne, is_not_empty), - self.data_timeout - )?; + nbError_to_Error!(busy_wait_cycles!(check_status_flag!(self.nb.i2c, rxne, is_not_empty), self.data_timeout)); Ok(self.nb.i2c.rxdr.read().rxdata().bits()) } /// Wait the write data register to be empty (ie for TXIS flag /// to be set) and write the byte to it - fn wait_byte_write(&self, byte: u8) -> NbResult<(), Error> { + fn wait_byte_write(&self, byte: u8) -> Result<(), Error> { // Wait until we are allowed to send data // (START has been ACKed or last byte when through) - busy_wait_cycles!( - check_status_flag!(self.nb.i2c, txis, is_empty), - self.data_timeout - )?; + nbError_to_Error!(busy_wait_cycles!(check_status_flag!(self.nb.i2c, txis, is_empty), self.data_timeout)); // Put byte on the wire self.nb.i2c.txdr.write(|w| w.txdata().bits(byte)); @@ -564,7 +588,7 @@ macro_rules! hal { } impl Write for BlockingI2c<$I2CX, SCL, SDA> { - type Error = NbError; + type Error = Error; /// Write bytes to I2C. Currently, `bytes.len()` must be less or /// equal than 255 @@ -592,7 +616,7 @@ macro_rules! hal { } impl Read for BlockingI2c<$I2CX, SCL, SDA> { - type Error = NbError; + type Error = Error; /// Reads enough bytes from slave with `address` to fill `buffer` fn read(&mut self, addr: u8, buffer: &mut [u8]) -> Result<(), Self::Error> { @@ -620,7 +644,7 @@ macro_rules! hal { } impl WriteRead for BlockingI2c<$I2CX, SCL, SDA> { - type Error = NbError; + type Error = Error; fn write_read( &mut self, @@ -642,10 +666,7 @@ macro_rules! hal { // Wait until the write finishes before beginning to read. // busy_wait2!(self.nb.i2c, tc, is_complete); - busy_wait_cycles!( - check_status_flag!(self.nb.i2c, tc, is_complete), - self.data_timeout - )?; + nbError_to_Error!(busy_wait_cycles!(check_status_flag!(self.nb.i2c, tc, is_complete), self.data_timeout)); // reSTART and prepare to receive bytes into `buffer` self.nb.start(addr, buffer.len() as u8, true, true); diff --git a/src/prelude.rs b/src/prelude.rs index df503a3..d370bae 100644 --- a/src/prelude.rs +++ b/src/prelude.rs @@ -4,7 +4,6 @@ pub use embedded_time::{duration::Extensions as _, rate::Extensions as _}; pub use crate::fmc::FmcExt as _stm327xx_hal_fmc_FmcExt; pub use crate::gpio::GpioExt as _stm327xx_hal_gpio_GpioExt; -pub use crate::hal::digital::v2::{InputPin, OutputPin}; -pub use crate::hal::prelude::*; +pub use crate::hal::digital::blocking::{InputPin, OutputPin}; pub use crate::rcc::RccExt as _stm32f7xx_hal_rcc_RccExt; pub use crate::rng::RngExt as _; diff --git a/src/rng.rs b/src/rng.rs index da1afa5..ec228b0 100644 --- a/src/rng.rs +++ b/src/rng.rs @@ -5,7 +5,6 @@ use crate::pac::{RCC, RNG}; use crate::rcc::{Enable, Reset}; use core::num::NonZeroU32; use core::ops::Shl; -use embedded_hal::blocking::rng::Read; use rand_core::RngCore; #[derive(Debug)] @@ -90,16 +89,19 @@ impl Rng { } } - pub fn release(self) -> RNG { - self.rb + /// Reads enough bytes from hardware random number generator to fill `buffer` + /// + /// If any error is encountered then this function immediately returns. The contents of buf are + /// unspecified in this case. + /// + /// If this function returns an error, it is unspecified how many bytes it has read, but it + /// will never read more than would be necessary to completely fill the buffer. + pub fn read(&mut self, buffer: &mut [u8]) -> Result<(), rand_core::Error> { + self.try_fill_bytes(buffer) } -} -impl Read for Rng { - type Error = rand_core::Error; - - fn read(&mut self, buffer: &mut [u8]) -> Result<(), Self::Error> { - self.try_fill_bytes(buffer) + pub fn release(self) -> RNG { + self.rb } } diff --git a/src/serial.rs b/src/serial.rs index c86013f..7dbe9b3 100644 --- a/src/serial.rs +++ b/src/serial.rs @@ -6,10 +6,10 @@ use core::pin::Pin; use core::ptr; use as_slice::{AsMutSlice, AsSlice}; +use embedded_hal::serial::nb::{Read, Write}; use crate::dma; use crate::embedded_time::rate::Extensions as _; -use crate::hal::prelude::*; use crate::hal::serial; use crate::pac; use crate::rcc::{Enable, Reset}; @@ -34,20 +34,6 @@ use crate::gpio::{ use crate::embedded_time::rate::BytesPerSecond; use crate::rcc::Clocks; -/// Serial error -#[derive(Debug)] -#[non_exhaustive] -pub enum Error { - /// Framing error - Framing, - /// Noise error - Noise, - /// RX buffer overrun - Overrun, - /// Parity check error - Parity, -} - pub trait Pins {} pub trait PinTx {} pub trait PinRx {} @@ -231,13 +217,13 @@ where } } -impl serial::Read for Serial +impl Read for Serial where USART: Instance, { - type Error = Error; + type Error = serial::ErrorKind; - fn read(&mut self) -> nb::Result { + fn read(&mut self) -> nb::Result { let mut rx: Rx = Rx { _usart: PhantomData, }; @@ -245,11 +231,11 @@ where } } -impl serial::Write for Serial +impl Write for Serial where USART: Instance, { - type Error = Error; + type Error = serial::ErrorKind; fn flush(&mut self) -> nb::Result<(), Self::Error> { let mut tx: Tx = Tx { @@ -309,13 +295,13 @@ where } } -impl serial::Read for Rx +impl serial::nb::Read for Rx where USART: Instance, { - type Error = Error; + type Error = serial::ErrorKind; - fn read(&mut self) -> nb::Result { + fn read(&mut self) -> nb::Result { // NOTE(unsafe) atomic read with no side effects let isr = unsafe { (*USART::ptr()).isr.read() }; @@ -324,19 +310,19 @@ where if isr.pe().bit_is_set() { icr.write(|w| w.pecf().clear()); - return Err(nb::Error::Other(Error::Parity)); + return Err(nb::Error::Other(Self::Error::Parity)); } if isr.fe().bit_is_set() { icr.write(|w| w.fecf().clear()); - return Err(nb::Error::Other(Error::Framing)); + return Err(nb::Error::Other(Self::Error::FrameFormat)); } if isr.nf().bit_is_set() { icr.write(|w| w.ncf().clear()); - return Err(nb::Error::Other(Error::Noise)); + return Err(nb::Error::Other(Self::Error::Noise)); } if isr.ore().bit_is_set() { icr.write(|w| w.orecf().clear()); - return Err(nb::Error::Other(Error::Overrun)); + return Err(nb::Error::Other(Self::Error::Overrun)); } if isr.rxne().bit_is_set() { @@ -398,11 +384,11 @@ where } } -impl serial::Write for Tx +impl serial::nb::Write for Tx where USART: Instance, { - type Error = Error; + type Error = serial::ErrorKind; fn flush(&mut self) -> nb::Result<(), Self::Error> { // NOTE(unsafe) atomic read with no side effects @@ -502,7 +488,7 @@ impl_instance! { impl fmt::Write for Tx where - Tx: serial::Write, + Tx: serial::nb::Write, { fn write_str(&mut self, s: &str) -> fmt::Result { let _ = s.as_bytes().iter().map(|c| block!(self.write(*c))).last(); diff --git a/src/spi.rs b/src/spi.rs index bf4c5d6..2d44d53 100644 --- a/src/spi.rs +++ b/src/spi.rs @@ -8,9 +8,12 @@ pub use embedded_hal::spi::{Mode, Phase, Polarity}; use core::{fmt, marker::PhantomData, ops::DerefMut, pin::Pin, ptr}; use as_slice::{AsMutSlice, AsSlice as _}; -use embedded_hal::{ - blocking::spi::{transfer, write, write_iter}, - spi::FullDuplex, +use embedded_hal::spi::{ + self, + { + blocking::{TransferInplace, Write, WriteIter}, + nb::FullDuplex, + }, }; use crate::{ @@ -178,39 +181,72 @@ where P: Pins, Word: SupportedWordSize, { - type Error = Error; + type Error = spi::ErrorKind; fn read(&mut self) -> nb::Result { self.spi.read() } - fn send(&mut self, word: Word) -> nb::Result<(), Self::Error> { + fn write(&mut self, word: Word) -> nb::Result<(), Self::Error> { self.spi.send(word) } } -impl transfer::Default for Spi> +impl TransferInplace for Spi> where I: Instance, P: Pins, - Word: SupportedWordSize, + Word: SupportedWordSize + Clone, { + type Error = spi::ErrorKind; + + fn transfer_inplace(&mut self, words: &mut [Word]) -> Result<(), Self::Error> { + for word in words.iter_mut() { + nb::block!(FullDuplex::write(self, word.clone()))?; + *word = nb::block!(FullDuplex::read(self))?; + } + + Ok(()) + } } -impl write::Default for Spi> +impl Write for Spi> where I: Instance, P: Pins, - Word: SupportedWordSize, + Word: SupportedWordSize + Clone, { + type Error = spi::ErrorKind; + + fn write(&mut self, words: &[Word]) -> Result<(), Self::Error> { + for word in words { + nb::block!(FullDuplex::write(self, word.clone()))?; + nb::block!(FullDuplex::read(self))?; + } + + Ok(()) + } } -impl write_iter::Default for Spi> +impl WriteIter for Spi> where I: Instance, P: Pins, - Word: SupportedWordSize, + Word: SupportedWordSize + Clone, { + type Error = spi::ErrorKind; + + fn write_iter(&mut self, words: WI) -> Result<(), Self::Error> + where + WI: IntoIterator, + { + for word in words.into_iter() { + nb::block!(FullDuplex::write(self, word.clone()))?; + nb::block!(FullDuplex::read(self))?; + } + + Ok(()) + } } impl Spi @@ -231,10 +267,10 @@ pub trait Instance { fn configure(&self, br: u8, cpol: bool, cpha: bool) where Word: SupportedWordSize; - fn read(&self) -> nb::Result + fn read(&self) -> nb::Result where Word: SupportedWordSize; - fn send(&self, word: Word) -> nb::Result<(), Error> + fn send(&self, word: Word) -> nb::Result<(), spi::ErrorKind> where Word: SupportedWordSize; fn dr_address(&self) -> u32; @@ -348,7 +384,7 @@ macro_rules! impl_instance { ); } - fn read(&self) -> nb::Result { + fn read(&self) -> nb::Result { let sr = self.sr.read(); // Check for errors @@ -358,13 +394,13 @@ macro_rules! impl_instance { // SPI types in the PAC, explained in more detail in // another comment. if sr.fre().is_error() { - return Err(nb::Error::Other(Error::FrameFormat)); + return Err(nb::Error::Other(spi::ErrorKind::FrameFormat)); } if sr.ovr().is_overrun() { - return Err(nb::Error::Other(Error::Overrun)); + return Err(nb::Error::Other(spi::ErrorKind::Overrun)); } if sr.modf().is_fault() { - return Err(nb::Error::Other(Error::ModeFault)); + return Err(nb::Error::Other(spi::ErrorKind::ModeFault)); } // Did we receive something? @@ -385,7 +421,7 @@ macro_rules! impl_instance { Err(nb::Error::WouldBlock) } - fn send(&self, word: Word) -> nb::Result<(), Error> { + fn send(&self, word: Word) -> nb::Result<(), spi::ErrorKind> { let sr = self.sr.read(); // Check for errors @@ -395,13 +431,13 @@ macro_rules! impl_instance { // SPI types in the PAC, explained in more detail in // another comment. if sr.fre().is_error() { - return Err(nb::Error::Other(Error::FrameFormat)); + return Err(nb::Error::Other(spi::ErrorKind::FrameFormat)); } if sr.ovr().is_overrun() { - return Err(nb::Error::Other(Error::Overrun)); + return Err(nb::Error::Other(spi::ErrorKind::Overrun)); } if sr.modf().is_fault() { - return Err(nb::Error::Other(Error::ModeFault)); + return Err(nb::Error::Other(spi::ErrorKind::ModeFault)); } // Can we write to the transmit buffer? @@ -582,13 +618,6 @@ impl Miso for NoMiso {} pub struct NoMosi; impl Mosi for NoMosi {} -#[derive(Debug)] -pub enum Error { - FrameFormat, - Overrun, - ModeFault, -} - /// RX token used for DMA transfers pub struct Rx(PhantomData); diff --git a/src/timer.rs b/src/timer.rs index 1da788e..30c1cdb 100644 --- a/src/timer.rs +++ b/src/timer.rs @@ -1,14 +1,16 @@ //! Timers use crate::embedded_time::rate::Hertz; -use crate::hal::timer::{Cancel, CountDown, Periodic}; +use crate::hal::timer::{ + nb::{Cancel, CountDown}, + Periodic, +}; use crate::pac::{ TIM1, TIM10, TIM11, TIM12, TIM13, TIM14, TIM2, TIM3, TIM4, TIM5, TIM6, TIM7, TIM8, TIM9, }; use crate::rcc::{Clocks, Enable, RccBus, Reset}; use cast::{u16, u32}; use nb; -use void::Void; /// Hardware timers pub struct Timer { @@ -25,12 +27,28 @@ pub enum Event { } /// Timer errors -#[derive(Debug, PartialEq)] -pub enum Error { +pub trait Error: core::fmt::Debug { + /// Convert error to a generic SPI error kind + /// + /// By using this method, SPI errors freely defined by HAL implementations + /// can be converted to a set of generic SPI errors upon which generic + /// code can act. + fn kind(&self) -> ErrorKind; +} + +#[derive(Debug, Copy, Clone, Eq, PartialEq, Ord, PartialOrd, Hash)] +#[non_exhaustive] +pub enum ErrorKind { /// Timer is disabled. Disabled, } +impl Error for ErrorKind { + fn kind(&self) -> ErrorKind { + *self + } +} + macro_rules! hal { ($($TIM:ident: ($tim:ident, $timclk:ident),)+) => { $( @@ -38,9 +56,10 @@ macro_rules! hal { impl CountDown for Timer<$TIM> { type Time = Hertz; + type Error = ErrorKind; #[allow(unused_unsafe)] - fn start(&mut self, timeout: T) + fn start(&mut self, timeout: T) -> core::result::Result<(), Self::Error> where T: Into, { @@ -65,9 +84,11 @@ macro_rules! hal { self.tim.sr.modify(|_, w| w.uif().clear_bit()); self.enable(); + + Ok(()) } - fn wait(&mut self) -> nb::Result<(), Void> { + fn wait(&mut self) -> nb::Result<(), Self::Error> { if self.tim.sr.read().uif().bit_is_clear() { Err(nb::Error::WouldBlock) } else { @@ -78,11 +99,9 @@ macro_rules! hal { } impl Cancel for Timer<$TIM> { - type Error = Error; - fn cancel(&mut self) -> Result<(), Self::Error> { if !self.tim.cr1.read().cen().is_enabled() { - return Err(Error::Disabled); + return Err(ErrorKind::Disabled); } self.disable(); @@ -93,7 +112,7 @@ macro_rules! hal { impl Timer<$TIM> { /// Configures a TIM peripheral as a periodic count down timer - pub fn $tim(tim: $TIM, timeout: T, clocks: Clocks, apb: &mut <$TIM as RccBus>::Bus) -> Self + pub fn $tim(tim: $TIM, timeout: T, clocks: Clocks, apb: &mut <$TIM as RccBus>::Bus) -> core::result::Result where T: Into, { @@ -108,9 +127,9 @@ macro_rules! hal { tim, timeout: Hertz(0), }; - timer.start(timeout); + timer.start(timeout)?; - timer + Ok(timer) } /// Starts listening for an `event`