From 2ec81419fa7ca1d1d4c797c1d416c1f226aefb33 Mon Sep 17 00:00:00 2001 From: Daniel Trnka Date: Sat, 21 Dec 2024 22:01:36 +0100 Subject: [PATCH 1/4] stm32/usart: configurable readback in half-duplex mode --- embassy-stm32/src/usart/mod.rs | 54 +++++++++++++++++++++++++++------- 1 file changed, 44 insertions(+), 10 deletions(-) diff --git a/embassy-stm32/src/usart/mod.rs b/embassy-stm32/src/usart/mod.rs index 2d801e6bf8..98b5c9cfe2 100644 --- a/embassy-stm32/src/usart/mod.rs +++ b/embassy-stm32/src/usart/mod.rs @@ -125,6 +125,33 @@ pub enum StopBits { STOP1P5, } +#[derive(Clone, Copy, PartialEq, Eq, Debug)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +/// Enables or disables receiver so written data are read back in half-duplex mode +pub enum HalfDuplexReadback { + /// Disables receiver so written data are not read back + NoReadback, + /// Enables receiver so written data are read back + Readback, +} + +#[derive(Clone, Copy, PartialEq, Eq, Debug)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +/// Duplex mode +pub enum Duplex { + /// Full duplex + Full, + /// Half duplex with possibility to read back written data + Half(HalfDuplexReadback), +} + +impl Duplex { + /// Returns true if half-duplex + fn is_half(&self) -> bool { + matches!(self, Duplex::Half(_)) + } +} + #[non_exhaustive] #[derive(Clone, Copy, PartialEq, Eq, Debug)] #[cfg_attr(feature = "defmt", derive(defmt::Format))] @@ -181,7 +208,7 @@ pub struct Config { pub rx_pull: Pull, // private: set by new_half_duplex, not by the user. - half_duplex: bool, + duplex: Duplex, } impl Config { @@ -220,7 +247,7 @@ impl Default for Config { #[cfg(any(usart_v3, usart_v4))] invert_rx: false, rx_pull: Pull::None, - half_duplex: false, + duplex: Duplex::Full, } } } @@ -308,6 +335,7 @@ pub struct UartTx<'d, M: Mode> { cts: Option>, de: Option>, tx_dma: Option>, + duplex: Duplex, _phantom: PhantomData, } @@ -413,7 +441,7 @@ impl<'d> UartTx<'d, Async> { let mut cr1 = r.cr1().read(); if r.cr3().read().hdsel() && !cr1.te() { cr1.set_te(true); - cr1.set_re(false); + cr1.set_re(self.duplex == Duplex::Half(HalfDuplexReadback::Readback)); r.cr1().write_value(cr1); } @@ -485,6 +513,7 @@ impl<'d, M: Mode> UartTx<'d, M> { cts, de: None, tx_dma, + duplex: config.duplex, _phantom: PhantomData, }; this.enable_and_configure(&config)?; @@ -519,7 +548,7 @@ impl<'d, M: Mode> UartTx<'d, M> { let mut cr1 = r.cr1().read(); if r.cr3().read().hdsel() && !cr1.te() { cr1.set_te(true); - cr1.set_re(false); + cr1.set_re(self.duplex == Duplex::Half(HalfDuplexReadback::Readback)); r.cr1().write_value(cr1); } @@ -1149,13 +1178,14 @@ impl<'d> Uart<'d, Async> { tx_dma: impl Peripheral

> + 'd, rx_dma: impl Peripheral

> + 'd, mut config: Config, + readback: HalfDuplexReadback, half_duplex: HalfDuplexConfig, ) -> Result { #[cfg(not(any(usart_v1, usart_v2)))] { config.swap_rx_tx = false; } - config.half_duplex = true; + config.duplex = Duplex::Half(readback); Self::new_inner( peri, @@ -1188,10 +1218,11 @@ impl<'d> Uart<'d, Async> { tx_dma: impl Peripheral

> + 'd, rx_dma: impl Peripheral

> + 'd, mut config: Config, + readback: HalfDuplexReadback, half_duplex: HalfDuplexConfig, ) -> Result { config.swap_rx_tx = true; - config.half_duplex = true; + config.duplex = Duplex::Half(readback); Self::new_inner( peri, @@ -1307,13 +1338,14 @@ impl<'d> Uart<'d, Blocking> { peri: impl Peripheral

+ 'd, tx: impl Peripheral

> + 'd, mut config: Config, + readback: HalfDuplexReadback, half_duplex: HalfDuplexConfig, ) -> Result { #[cfg(not(any(usart_v1, usart_v2)))] { config.swap_rx_tx = false; } - config.half_duplex = true; + config.duplex = Duplex::Half(readback); Self::new_inner( peri, @@ -1343,10 +1375,11 @@ impl<'d> Uart<'d, Blocking> { peri: impl Peripheral

+ 'd, rx: impl Peripheral

> + 'd, mut config: Config, + readback: HalfDuplexReadback, half_duplex: HalfDuplexConfig, ) -> Result { config.swap_rx_tx = true; - config.half_duplex = true; + config.duplex = Duplex::Half(readback); Self::new_inner( peri, @@ -1388,6 +1421,7 @@ impl<'d, M: Mode> Uart<'d, M> { cts, de, tx_dma, + duplex: config.duplex, }, rx: UartRx { _phantom: PhantomData, @@ -1667,14 +1701,14 @@ fn configure( r.cr3().modify(|w| { #[cfg(not(usart_v1))] w.set_onebit(config.assume_noise_free); - w.set_hdsel(config.half_duplex); + w.set_hdsel(config.duplex.is_half()); }); r.cr1().write(|w| { // enable uart w.set_ue(true); - if config.half_duplex { + if config.duplex.is_half() { // The te and re bits will be set by write, read and flush methods. // Receiver should be enabled by default for Half-Duplex. w.set_te(false); From 7b7ac1bd3ea2eb4897b8fcab706da968188bb700 Mon Sep 17 00:00:00 2001 From: Daniel Trnka Date: Sun, 22 Dec 2024 12:53:05 +0100 Subject: [PATCH 2/4] stm32/usart: disabling receiver before write in half-duplex moved to a new function --- embassy-stm32/src/usart/mod.rs | 27 +++++++++++++-------------- 1 file changed, 13 insertions(+), 14 deletions(-) diff --git a/embassy-stm32/src/usart/mod.rs b/embassy-stm32/src/usart/mod.rs index 98b5c9cfe2..48cc4f6d6b 100644 --- a/embassy-stm32/src/usart/mod.rs +++ b/embassy-stm32/src/usart/mod.rs @@ -437,13 +437,7 @@ impl<'d> UartTx<'d, Async> { pub async fn write(&mut self, buffer: &[u8]) -> Result<(), Error> { let r = self.info.regs; - // Enable Transmitter and disable Receiver for Half-Duplex mode - let mut cr1 = r.cr1().read(); - if r.cr3().read().hdsel() && !cr1.te() { - cr1.set_te(true); - cr1.set_re(self.duplex == Duplex::Half(HalfDuplexReadback::Readback)); - r.cr1().write_value(cr1); - } + half_duplex_set_rx_tx_before_write(&r, self.duplex == Duplex::Half(HalfDuplexReadback::Readback)); let ch = self.tx_dma.as_mut().unwrap(); r.cr3().modify(|reg| { @@ -544,13 +538,7 @@ impl<'d, M: Mode> UartTx<'d, M> { pub fn blocking_write(&mut self, buffer: &[u8]) -> Result<(), Error> { let r = self.info.regs; - // Enable Transmitter and disable Receiver for Half-Duplex mode - let mut cr1 = r.cr1().read(); - if r.cr3().read().hdsel() && !cr1.te() { - cr1.set_te(true); - cr1.set_re(self.duplex == Duplex::Half(HalfDuplexReadback::Readback)); - r.cr1().write_value(cr1); - } + half_duplex_set_rx_tx_before_write(&r, self.duplex == Duplex::Half(HalfDuplexReadback::Readback)); for &b in buffer { while !sr(r).read().txe() {} @@ -629,6 +617,17 @@ pub fn send_break(regs: &Regs) { regs.rqr().write(|w| w.set_sbkrq(true)); } +/// Enable Transmitter and disable Receiver for Half-Duplex mode +/// In case of readback, keep Receiver enabled +fn half_duplex_set_rx_tx_before_write(r: &Regs, enable_readback: bool) { + let mut cr1 = r.cr1().read(); + if r.cr3().read().hdsel() && !cr1.te() { + cr1.set_te(true); + cr1.set_re(enable_readback); + r.cr1().write_value(cr1); + } +} + impl<'d> UartRx<'d, Async> { /// Create a new rx-only UART with no hardware flow control. /// From a7983668da2947f7846f0abc4736708539aedc42 Mon Sep 17 00:00:00 2001 From: Daniel Trnka Date: Sat, 21 Dec 2024 13:29:00 +0100 Subject: [PATCH 3/4] stm32/usart: half-duplex support for buffered usart --- embassy-stm32/src/usart/buffered.rs | 100 +++++++++++++++++++++++++++- 1 file changed, 98 insertions(+), 2 deletions(-) diff --git a/embassy-stm32/src/usart/buffered.rs b/embassy-stm32/src/usart/buffered.rs index 814be2858a..7bbe01a00d 100644 --- a/embassy-stm32/src/usart/buffered.rs +++ b/embassy-stm32/src/usart/buffered.rs @@ -12,8 +12,9 @@ use embassy_sync::waitqueue::AtomicWaker; #[cfg(not(any(usart_v1, usart_v2)))] use super::DePin; use super::{ - clear_interrupt_flags, configure, rdr, reconfigure, send_break, set_baudrate, sr, tdr, Config, ConfigError, CtsPin, - Error, Info, Instance, Regs, RtsPin, RxPin, TxPin, + clear_interrupt_flags, configure, half_duplex_set_rx_tx_before_write, rdr, reconfigure, send_break, set_baudrate, + sr, tdr, Config, ConfigError, CtsPin, Duplex, Error, HalfDuplexConfig, HalfDuplexReadback, Info, Instance, Regs, + RtsPin, RxPin, TxPin, }; use crate::gpio::{AfType, AnyPin, OutputType, Pull, SealedPin as _, Speed}; use crate::interrupt::{self, InterruptExt}; @@ -108,6 +109,8 @@ unsafe fn on_interrupt(r: Regs, state: &'static State) { }); } + half_duplex_set_rx_tx_before_write(&r, state.half_duplex_readback.load(Ordering::Relaxed)); + tdr(r).write_volatile(buf[0].into()); tx_reader.pop_done(1); } else { @@ -126,6 +129,7 @@ pub(super) struct State { tx_buf: RingBuffer, tx_done: AtomicBool, tx_rx_refcount: AtomicU8, + half_duplex_readback: AtomicBool, } impl State { @@ -137,6 +141,7 @@ impl State { tx_waker: AtomicWaker::new(), tx_done: AtomicBool::new(true), tx_rx_refcount: AtomicU8::new(0), + half_duplex_readback: AtomicBool::new(false), } } } @@ -321,6 +326,84 @@ impl<'d> BufferedUart<'d> { ) } + /// Create a single-wire half-duplex Uart transceiver on a single Tx pin. + /// + /// See [`new_half_duplex_on_rx`][`Self::new_half_duplex_on_rx`] if you would prefer to use an Rx pin + /// (when it is available for your chip). There is no functional difference between these methods, as both + /// allow bidirectional communication. + /// + /// The TX pin is always released when no data is transmitted. Thus, it acts as a standard + /// I/O in idle or in reception. It means that the I/O must be configured so that TX is + /// configured as alternate function open-drain with an external pull-up + /// Apart from this, the communication protocol is similar to normal USART mode. Any conflict + /// on the line must be managed by software (for instance by using a centralized arbiter). + #[doc(alias("HDSEL"))] + pub fn new_half_duplex( + peri: impl Peripheral

+ 'd, + tx: impl Peripheral

> + 'd, + _irq: impl interrupt::typelevel::Binding> + 'd, + tx_buffer: &'d mut [u8], + rx_buffer: &'d mut [u8], + mut config: Config, + readback: HalfDuplexReadback, + half_duplex: HalfDuplexConfig, + ) -> Result { + #[cfg(not(any(usart_v1, usart_v2)))] + { + config.swap_rx_tx = false; + } + config.duplex = Duplex::Half(readback); + + Self::new_inner( + peri, + None, + new_pin!(tx, half_duplex.af_type()), + None, + None, + None, + tx_buffer, + rx_buffer, + config, + ) + } + + /// Create a single-wire half-duplex Uart transceiver on a single Rx pin. + /// + /// See [`new_half_duplex`][`Self::new_half_duplex`] if you would prefer to use an Tx pin. + /// There is no functional difference between these methods, as both allow bidirectional communication. + /// + /// The pin is always released when no data is transmitted. Thus, it acts as a standard + /// I/O in idle or in reception. + /// Apart from this, the communication protocol is similar to normal USART mode. Any conflict + /// on the line must be managed by software (for instance by using a centralized arbiter). + #[cfg(not(any(usart_v1, usart_v2)))] + #[doc(alias("HDSEL"))] + pub fn new_half_duplex_on_rx( + peri: impl Peripheral

+ 'd, + rx: impl Peripheral

> + 'd, + _irq: impl interrupt::typelevel::Binding> + 'd, + tx_buffer: &'d mut [u8], + rx_buffer: &'d mut [u8], + mut config: Config, + readback: HalfDuplexReadback, + half_duplex: HalfDuplexConfig, + ) -> Result { + config.swap_rx_tx = true; + config.duplex = Duplex::Half(readback); + + Self::new_inner( + peri, + new_pin!(rx, half_duplex.af_type()), + None, + None, + None, + None, + tx_buffer, + rx_buffer, + config, + ) + } + fn new_inner( _peri: impl Peripheral

+ 'd, rx: Option>, @@ -336,6 +419,11 @@ impl<'d> BufferedUart<'d> { let state = T::buffered_state(); let kernel_clock = T::frequency(); + state.half_duplex_readback.store( + config.duplex == Duplex::Half(HalfDuplexReadback::Readback), + Ordering::Relaxed, + ); + let mut this = Self { rx: BufferedUartRx { info, @@ -381,12 +469,20 @@ impl<'d> BufferedUart<'d> { w.set_ctse(self.tx.cts.is_some()); #[cfg(not(any(usart_v1, usart_v2)))] w.set_dem(self.tx.de.is_some()); + w.set_hdsel(config.duplex.is_half()); }); configure(info, self.rx.kernel_clock, &config, true, true)?; info.regs.cr1().modify(|w| { w.set_rxneie(true); w.set_idleie(true); + + if config.duplex.is_half() { + // The te and re bits will be set by write, read and flush methods. + // Receiver should be enabled by default for Half-Duplex. + w.set_te(false); + w.set_re(true); + } }); info.interrupt.unpend(); From 7070f5364eb903c6c6b0b28348a582f5a9e1f89e Mon Sep 17 00:00:00 2001 From: Daniel Trnka Date: Sun, 22 Dec 2024 17:37:20 +0100 Subject: [PATCH 4/4] examples/stm32g0: added ds18b20 temperature sensor on 1-wire bus --- examples/stm32g0/src/bin/onewire_ds18b20.rs | 271 ++++++++++++++++++++ 1 file changed, 271 insertions(+) create mode 100644 examples/stm32g0/src/bin/onewire_ds18b20.rs diff --git a/examples/stm32g0/src/bin/onewire_ds18b20.rs b/examples/stm32g0/src/bin/onewire_ds18b20.rs new file mode 100644 index 0000000000..f85cc4ff8f --- /dev/null +++ b/examples/stm32g0/src/bin/onewire_ds18b20.rs @@ -0,0 +1,271 @@ +//! This examples shows how you can use buffered or DMA UART to read a DS18B20 temperature sensor on 1-Wire bus. +//! Connect 5k pull-up resistor between PA9 and 3.3V. +#![no_std] +#![no_main] + +use cortex_m::singleton; +use defmt::*; +use embassy_executor::Spawner; +use embassy_stm32::mode::Async; +use embassy_stm32::usart::{ + BufferedUartRx, BufferedUartTx, Config, ConfigError, HalfDuplexConfig, RingBufferedUartRx, UartTx, +}; +use embassy_stm32::{bind_interrupts, peripherals, usart}; +use embassy_time::{Duration, Timer}; +use {defmt_rtt as _, panic_probe as _}; + +/// Create onewire bus using DMA USART +fn create_onewire(p: embassy_stm32::Peripherals) -> OneWire, RingBufferedUartRx<'static>> { + use embassy_stm32::usart::Uart; + bind_interrupts!(struct Irqs { + USART1 => usart::InterruptHandler; + }); + + let usart = Uart::new_half_duplex( + p.USART1, + p.PA9, + Irqs, + p.DMA1_CH1, + p.DMA1_CH2, + Config::default(), + // Enable readback so we can read sensor pulling data low while transmission is in progress + usart::HalfDuplexReadback::Readback, + HalfDuplexConfig::OpenDrainExternal, + ) + .unwrap(); + + const BUFFER_SIZE: usize = 16; + let (tx, rx) = usart.split(); + let rx_buf: &mut [u8; BUFFER_SIZE] = singleton!(TX_BUF: [u8; BUFFER_SIZE] = [0; BUFFER_SIZE]).unwrap(); + let rx = rx.into_ring_buffered(rx_buf); + OneWire::new(tx, rx) +} + +/* +/// Create onewire bus using buffered USART +fn create_onewire(p: embassy_stm32::Peripherals) -> OneWire, BufferedUartRx<'static>> { + use embassy_stm32::usart::BufferedUart; + bind_interrupts!(struct Irqs { + USART1 => usart::BufferedInterruptHandler; + }); + + const BUFFER_SIZE: usize = 16; + let tx_buf: &mut [u8; BUFFER_SIZE] = singleton!(TX_BUF: [u8; BUFFER_SIZE] = [0; BUFFER_SIZE]).unwrap(); + let rx_buf: &mut [u8; BUFFER_SIZE] = singleton!(RX_BUF: [u8; BUFFER_SIZE] = [0; BUFFER_SIZE]).unwrap(); + let usart = BufferedUart::new_half_duplex( + p.USART1, + p.PA9, + Irqs, + tx_buf, + rx_buf, + Config::default(), + // Enable readback so we can read sensor pulling data low while transmission is in progress + usart::HalfDuplexReadback::Readback, + HalfDuplexConfig::OpenDrainExternal, + ) + .unwrap(); + let (tx, rx) = usart.split(); + OneWire::new(tx, rx) +} +*/ + +#[embassy_executor::main] +async fn main(_spawner: Spawner) { + let p = embassy_stm32::init(Default::default()); + + let onewire = create_onewire(p); + let mut sensor = Ds18b20::new(onewire); + + loop { + // Start a new temperature measurement + sensor.start().await; + // Wait for the measurement to finish + Timer::after(Duration::from_secs(1)).await; + match sensor.temperature().await { + Ok(temp) => info!("temp = {:?} deg C", temp), + _ => error!("sensor error"), + } + Timer::after(Duration::from_secs(1)).await; + } +} + +pub trait SetBaudrate { + fn set_baudrate(&mut self, baudrate: u32) -> Result<(), ConfigError>; +} +impl SetBaudrate for BufferedUartTx<'_> { + fn set_baudrate(&mut self, baudrate: u32) -> Result<(), ConfigError> { + BufferedUartTx::set_baudrate(self, baudrate) + } +} +impl SetBaudrate for BufferedUartRx<'_> { + fn set_baudrate(&mut self, baudrate: u32) -> Result<(), ConfigError> { + BufferedUartRx::set_baudrate(self, baudrate) + } +} +impl SetBaudrate for RingBufferedUartRx<'_> { + fn set_baudrate(&mut self, baudrate: u32) -> Result<(), ConfigError> { + RingBufferedUartRx::set_baudrate(self, baudrate) + } +} +impl SetBaudrate for UartTx<'_, Async> { + fn set_baudrate(&mut self, baudrate: u32) -> Result<(), ConfigError> { + UartTx::set_baudrate(self, baudrate) + } +} + +/// Simplified OneWire bus driver +pub struct OneWire +where + TX: embedded_io_async::Write + SetBaudrate, + RX: embedded_io_async::Read + SetBaudrate, +{ + tx: TX, + rx: RX, +} + +impl OneWire +where + TX: embedded_io_async::Write + SetBaudrate, + RX: embedded_io_async::Read + SetBaudrate, +{ + // bitrate with one bit taking ~104 us + const RESET_BUADRATE: u32 = 9600; + // bitrate with one bit taking ~8.7 us + const BAUDRATE: u32 = 115200; + + // startbit + 8 low bits = 9 * 1/115200 = 78 us low pulse + const LOGIC_1_CHAR: u8 = 0xFF; + // startbit only = 1/115200 = 8.7 us low pulse + const LOGIC_0_CHAR: u8 = 0x00; + + // Address all devices on the bus + const COMMAND_SKIP_ROM: u8 = 0xCC; + + pub fn new(tx: TX, rx: RX) -> Self { + Self { tx, rx } + } + + fn set_baudrate(&mut self, baudrate: u32) -> Result<(), ConfigError> { + self.tx.set_baudrate(baudrate)?; + self.rx.set_baudrate(baudrate) + } + + /// Reset the bus by at least 480 us low pulse. + pub async fn reset(&mut self) { + // Switch to 9600 baudrate, so one bit takes ~104 us + self.set_baudrate(Self::RESET_BUADRATE).expect("set_baudrate failed"); + // Low USART start bit + 4x low bits = 5 * 104 us = 520 us low pulse + self.tx.write(&[0xF0]).await.expect("write failed"); + + // Read the value on the bus + let mut buffer = [0; 1]; + self.rx.read_exact(&mut buffer).await.expect("read failed"); + + // Switch back to 115200 baudrate, so one bit takes ~8.7 us + self.set_baudrate(Self::BAUDRATE).expect("set_baudrate failed"); + + // read and expect sensor pulled some high bits to low (device present) + if buffer[0] & 0xF != 0 || buffer[0] & 0xF0 == 0xF0 { + warn!("No device present"); + } + } + + /// Send byte and read response on the bus. + pub async fn write_read_byte(&mut self, byte: u8) -> u8 { + // One byte is sent as 8 UART characters + let mut tx = [0; 8]; + for (pos, char) in tx.iter_mut().enumerate() { + *char = if (byte >> pos) & 0x1 == 0x1 { + Self::LOGIC_1_CHAR + } else { + Self::LOGIC_0_CHAR + }; + } + self.tx.write_all(&tx).await.expect("write failed"); + + // Readback the value on the bus, sensors can pull logic 1 to 0 + let mut rx = [0; 8]; + self.rx.read_exact(&mut rx).await.expect("read failed"); + let mut bus_byte = 0; + for (pos, char) in rx.iter().enumerate() { + // if its 0xFF, sensor didnt pull the bus to low level + if *char == 0xFF { + bus_byte |= 1 << pos; + } + } + + bus_byte + } + + /// Read a byte from the bus. + pub async fn read_byte(&mut self) -> u8 { + self.write_read_byte(0xFF).await + } +} + +/// DS18B20 temperature sensor driver +pub struct Ds18b20 +where + TX: embedded_io_async::Write + SetBaudrate, + RX: embedded_io_async::Read + SetBaudrate, +{ + bus: OneWire, +} + +impl Ds18b20 +where + TX: embedded_io_async::Write + SetBaudrate, + RX: embedded_io_async::Read + SetBaudrate, +{ + /// Start a temperature conversion. + const FN_CONVERT_T: u8 = 0x44; + /// Read contents of the scratchpad containing the temperature. + const FN_READ_SCRATCHPAD: u8 = 0xBE; + + pub fn new(bus: OneWire) -> Self { + Self { bus } + } + + /// Start a new measurement. Allow at least 1000ms before getting `temperature`. + pub async fn start(&mut self) { + self.bus.reset().await; + self.bus.write_read_byte(OneWire::::COMMAND_SKIP_ROM).await; + self.bus.write_read_byte(Self::FN_CONVERT_T).await; + } + + /// Calculate CRC8 of the data + fn crc8(data: &[u8]) -> u8 { + let mut temp; + let mut data_byte; + let mut crc = 0; + for b in data { + data_byte = *b; + for _ in 0..8 { + temp = (crc ^ data_byte) & 0x01; + crc >>= 1; + if temp != 0 { + crc ^= 0x8C; + } + data_byte >>= 1; + } + } + crc + } + + /// Read the temperature. Ensure >1000ms has passed since `start` before calling this. + pub async fn temperature(&mut self) -> Result { + self.bus.reset().await; + self.bus.write_read_byte(OneWire::::COMMAND_SKIP_ROM).await; + self.bus.write_read_byte(Self::FN_READ_SCRATCHPAD).await; + + let mut data = [0; 9]; + for byte in data.iter_mut() { + *byte = self.bus.read_byte().await; + } + + match Self::crc8(&data) == 0 { + true => Ok(((data[1] as u16) << 8 | data[0] as u16) as f32 / 16.), + false => Err(()), + } + } +}