Run rustfmt.

This commit is contained in:
Dario Nieuwenhuis 2022-06-12 22:15:44 +02:00
parent 6199bdea71
commit a8703b7598
340 changed files with 1326 additions and 3020 deletions

View file

@ -2,18 +2,13 @@
#![no_main]
#![feature(type_alias_impl_trait)]
use defmt_rtt as _; // global logger
use panic_probe as _;
use defmt::*;
use embassy::executor::Spawner;
use embassy::time::{Duration, Timer};
use embassy_nrf::{
gpio::{Level, Output, OutputDrive},
peripherals::P0_13,
Peripherals,
};
use embassy_nrf::gpio::{Level, Output, OutputDrive};
use embassy_nrf::peripherals::P0_13;
use embassy_nrf::Peripherals;
use {defmt_rtt as _, panic_probe as _}; // global logger
#[embassy::task]
async fn blinker(mut led: Output<'static, P0_13>, interval: Duration) {

View file

@ -2,15 +2,11 @@
#![no_main]
#![feature(type_alias_impl_trait)]
use defmt_rtt as _;
use panic_probe as _;
use embassy::executor::Spawner;
use embassy_stm32::{
exti::ExtiInput,
gpio::{Input, Level, Output, Pull, Speed},
Peripherals,
};
use embassy_stm32::exti::ExtiInput;
use embassy_stm32::gpio::{Input, Level, Output, Pull, Speed};
use embassy_stm32::Peripherals;
use {defmt_rtt as _, panic_probe as _};
#[embassy::main]
async fn main(_s: Spawner, p: Peripherals) {

View file

@ -2,10 +2,8 @@
#![no_main]
use cortex_m_rt::entry;
use defmt_rtt as _;
use panic_probe as _;
use embassy_stm32::gpio::{Input, Level, Output, Pull, Speed};
use {defmt_rtt as _, panic_probe as _};
#[entry]
fn main() -> ! {

View file

@ -1,18 +1,15 @@
#![no_std]
#![no_main]
use defmt_rtt as _;
use panic_probe as _;
use core::cell::RefCell;
use cortex_m::interrupt::Mutex;
use cortex_m::peripheral::NVIC;
use cortex_m_rt::entry;
use embassy_stm32::{
gpio::{Input, Level, Output, Pin, Pull, Speed},
interrupt, pac,
peripherals::{PB14, PC13},
};
use embassy_stm32::gpio::{Input, Level, Output, Pin, Pull, Speed};
use embassy_stm32::peripherals::{PB14, PC13};
use embassy_stm32::{interrupt, pac};
use {defmt_rtt as _, panic_probe as _};
static BUTTON: Mutex<RefCell<Option<Input<'static, PC13>>>> = Mutex::new(RefCell::new(None));
static LED: Mutex<RefCell<Option<Output<'static, PB14>>>> = Mutex::new(RefCell::new(None));

View file

@ -1,12 +1,8 @@
#![no_std]
#![no_main]
use defmt_rtt as _;
use panic_probe as _;
use stm32_metapac as pac;
use pac::gpio::vals;
use {defmt_rtt as _, panic_probe as _, stm32_metapac as pac};
#[cortex_m_rt::entry]
fn main() -> ! {
@ -30,30 +26,18 @@ fn main() -> ! {
let gpioc = pac::GPIOC;
const BUTTON_PIN: usize = 13;
unsafe {
gpioc
.pupdr()
.modify(|w| w.set_pupdr(BUTTON_PIN, vals::Pupdr::PULLUP));
gpioc
.otyper()
.modify(|w| w.set_ot(BUTTON_PIN, vals::Ot::PUSHPULL));
gpioc
.moder()
.modify(|w| w.set_moder(BUTTON_PIN, vals::Moder::INPUT));
gpioc.pupdr().modify(|w| w.set_pupdr(BUTTON_PIN, vals::Pupdr::PULLUP));
gpioc.otyper().modify(|w| w.set_ot(BUTTON_PIN, vals::Ot::PUSHPULL));
gpioc.moder().modify(|w| w.set_moder(BUTTON_PIN, vals::Moder::INPUT));
}
// Setup LED
let gpiob = pac::GPIOB;
const LED_PIN: usize = 14;
unsafe {
gpiob
.pupdr()
.modify(|w| w.set_pupdr(LED_PIN, vals::Pupdr::FLOATING));
gpiob
.otyper()
.modify(|w| w.set_ot(LED_PIN, vals::Ot::PUSHPULL));
gpiob
.moder()
.modify(|w| w.set_moder(LED_PIN, vals::Moder::OUTPUT));
gpiob.pupdr().modify(|w| w.set_pupdr(LED_PIN, vals::Pupdr::FLOATING));
gpiob.otyper().modify(|w| w.set_ot(LED_PIN, vals::Ot::PUSHPULL));
gpiob.moder().modify(|w| w.set_moder(LED_PIN, vals::Moder::OUTPUT));
}
// Main loop

View file

@ -202,8 +202,7 @@ impl<const PAGE_SIZE: usize> BootLoader<PAGE_SIZE> {
// Ensure we have enough progress pages to store copy progress
assert!(
self.active.len() / PAGE_SIZE
<= (self.state.len()
- <<P as FlashProvider>::STATE as FlashConfig>::FLASH::WRITE_SIZE)
<= (self.state.len() - <<P as FlashProvider>::STATE as FlashConfig>::FLASH::WRITE_SIZE)
/ <<P as FlashProvider>::STATE as FlashConfig>::FLASH::WRITE_SIZE
);
@ -226,15 +225,12 @@ impl<const PAGE_SIZE: usize> BootLoader<PAGE_SIZE> {
// Overwrite magic and reset progress
let fstate = p.state().flash();
let aligned = Aligned(
[!P::STATE::ERASE_VALUE;
<<P as FlashProvider>::STATE as FlashConfig>::FLASH::WRITE_SIZE],
[!P::STATE::ERASE_VALUE; <<P as FlashProvider>::STATE as FlashConfig>::FLASH::WRITE_SIZE],
);
fstate.write(self.state.from as u32, &aligned.0)?;
fstate.erase(self.state.from as u32, self.state.to as u32)?;
let aligned = Aligned(
[BOOT_MAGIC;
<<P as FlashProvider>::STATE as FlashConfig>::FLASH::WRITE_SIZE],
);
let aligned =
Aligned([BOOT_MAGIC; <<P as FlashProvider>::STATE as FlashConfig>::FLASH::WRITE_SIZE]);
fstate.write(self.state.from as u32, &aligned.0)?;
}
}
@ -262,10 +258,7 @@ impl<const PAGE_SIZE: usize> BootLoader<PAGE_SIZE> {
let flash = p.flash();
let mut aligned = Aligned([!P::ERASE_VALUE; P::FLASH::WRITE_SIZE]);
for i in 0..max_index {
flash.read(
(self.state.from + write_size + i * write_size) as u32,
&mut aligned.0,
)?;
flash.read((self.state.from + write_size + i * write_size) as u32, &mut aligned.0)?;
if aligned.0 == [P::ERASE_VALUE; P::FLASH::WRITE_SIZE] {
return Ok(i);
}
@ -311,9 +304,7 @@ impl<const PAGE_SIZE: usize> BootLoader<PAGE_SIZE> {
offset += chunk.len();
}
p.active()
.flash()
.erase(to_page as u32, (to_page + PAGE_SIZE) as u32)?;
p.active().flash().erase(to_page as u32, (to_page + PAGE_SIZE) as u32)?;
let mut offset = to_page;
for chunk in buf.chunks(P::ACTIVE::BLOCK_SIZE) {
@ -343,9 +334,7 @@ impl<const PAGE_SIZE: usize> BootLoader<PAGE_SIZE> {
offset += chunk.len();
}
p.dfu()
.flash()
.erase(to_page as u32, (to_page + PAGE_SIZE) as u32)?;
p.dfu().flash().erase(to_page as u32, (to_page + PAGE_SIZE) as u32)?;
let mut offset = to_page;
for chunk in buf.chunks(P::DFU::BLOCK_SIZE) {
@ -609,9 +598,7 @@ impl FirmwareUpdater {
aligned[i] = 0;
}
flash.write(self.state.from as u32, aligned).await?;
flash
.erase(self.state.from as u32, self.state.to as u32)
.await?;
flash.erase(self.state.from as u32, self.state.to as u32).await?;
for i in 0..aligned.len() {
aligned[i] = magic;
@ -677,13 +664,15 @@ impl FirmwareUpdater {
#[cfg(test)]
mod tests {
use super::*;
use core::convert::Infallible;
use core::future::Future;
use embedded_storage::nor_flash::ErrorType;
use embedded_storage_async::nor_flash::AsyncReadNorFlash;
use futures::executor::block_on;
use super::*;
/*
#[test]
fn test_bad_magic() {
@ -810,11 +799,7 @@ mod tests {
assert_eq!(
State::Swap,
bootloader
.prepare_boot(&mut MultiFlashProvider::new(
&mut active,
&mut state,
&mut dfu,
))
.prepare_boot(&mut MultiFlashProvider::new(&mut active, &mut state, &mut dfu,))
.unwrap()
);
@ -858,11 +843,7 @@ mod tests {
assert_eq!(
State::Swap,
bootloader
.prepare_boot(&mut MultiFlashProvider::new(
&mut active,
&mut state,
&mut dfu,
))
.prepare_boot(&mut MultiFlashProvider::new(&mut active, &mut state, &mut dfu,))
.unwrap()
);
@ -876,9 +857,7 @@ mod tests {
}
}
struct MemFlash<const SIZE: usize, const ERASE_SIZE: usize, const WRITE_SIZE: usize>(
[u8; SIZE],
);
struct MemFlash<const SIZE: usize, const ERASE_SIZE: usize, const WRITE_SIZE: usize>([u8; SIZE]);
impl<const SIZE: usize, const ERASE_SIZE: usize, const WRITE_SIZE: usize> NorFlash
for MemFlash<SIZE, ERASE_SIZE, WRITE_SIZE>
@ -889,12 +868,7 @@ mod tests {
let from = from as usize;
let to = to as usize;
assert!(from % ERASE_SIZE == 0);
assert!(
to % ERASE_SIZE == 0,
"To: {}, erase size: {}",
to,
ERASE_SIZE
);
assert!(to % ERASE_SIZE == 0, "To: {}, erase size: {}", to, ERASE_SIZE);
for i in from..to {
self.0[i] = 0xFF;
}

View file

@ -6,14 +6,10 @@
mod fmt;
pub use embassy_boot::{
FirmwareUpdater, FlashConfig, FlashProvider, Partition, SingleFlashProvider,
};
use embassy_nrf::{
nvmc::{Nvmc, PAGE_SIZE},
peripherals::WDT,
wdt,
};
pub use embassy_boot::{FirmwareUpdater, FlashConfig, FlashProvider, Partition, SingleFlashProvider};
use embassy_nrf::nvmc::{Nvmc, PAGE_SIZE};
use embassy_nrf::peripherals::WDT;
use embassy_nrf::wdt;
use embedded_storage::nor_flash::{ErrorType, NorFlash, ReadNorFlash};
pub struct BootLoader {
@ -95,9 +91,7 @@ impl BootLoader {
let mut cmd = mbr::sd_mbr_command_t {
command: mbr::NRF_MBR_COMMANDS_SD_MBR_COMMAND_IRQ_FORWARD_ADDRESS_SET,
params: mbr::sd_mbr_command_t__bindgen_ty_1 {
irq_forward_address_set: mbr::sd_mbr_command_irq_forward_address_set_t {
address: addr,
},
irq_forward_address_set: mbr::sd_mbr_command_irq_forward_address_set_t { address: addr },
},
};
let ret = mbr::sd_mbr_command(&mut cmd);

View file

@ -2,10 +2,8 @@
#![no_main]
use cortex_m_rt::{entry, exception};
#[cfg(feature = "defmt")]
use defmt_rtt as _;
use embassy_boot_nrf::*;
use embassy_nrf::nvmc::Nvmc;

View file

@ -6,9 +6,7 @@
mod fmt;
pub use embassy_boot::{
FirmwareUpdater, FlashConfig, FlashProvider, Partition, SingleFlashProvider, State,
};
pub use embassy_boot::{FirmwareUpdater, FlashConfig, FlashProvider, Partition, SingleFlashProvider, State};
use embedded_storage::nor_flash::NorFlash;
pub struct BootLoader<const PAGE_SIZE: usize> {

View file

@ -2,10 +2,8 @@
#![no_main]
use cortex_m_rt::{entry, exception};
#[cfg(feature = "defmt")]
use defmt_rtt as _;
use embassy_boot_stm32::*;
use embassy_stm32::flash::{Flash, ERASE_SIZE};

View file

@ -1,9 +1,9 @@
use core::marker::PhantomData;
use crate::interrupt::{Interrupt, InterruptExt};
pub use embassy::executor::Executor;
use embassy::executor::{raw, SendSpawner};
pub use embassy::executor::Executor;
use crate::interrupt::{Interrupt, InterruptExt};
fn pend_by_number(n: u16) {
#[derive(Clone, Copy)]

View file

@ -1,9 +1,8 @@
use core::{mem, ptr};
use atomic_polyfill::{compiler_fence, AtomicPtr, Ordering};
use core::mem;
use core::ptr;
use cortex_m::peripheral::NVIC;
use embassy_hal_common::Unborrow;
pub use embassy_macros::cortex_m_interrupt_take as take;
/// Implementation detail, do not use outside embassy crates.

View file

@ -1,5 +1,6 @@
use core::marker::PhantomData;
use core::mem::MaybeUninit;
use cortex_m::peripheral::scb::VectActive;
use cortex_m::peripheral::{NVIC, SCB};
@ -53,13 +54,11 @@ impl<'a, S: PeripheralState> PeripheralMutex<'a, S> {
/// Create a new `PeripheralMutex` wrapping `irq`, with `init` initializing the initial state.
///
/// Registers `on_interrupt` as the `irq`'s handler, and enables it.
pub fn new(
irq: S::Interrupt,
storage: &'a mut StateStorage<S>,
init: impl FnOnce() -> S,
) -> Self {
pub fn new(irq: S::Interrupt, storage: &'a mut StateStorage<S>, init: impl FnOnce() -> S) -> Self {
if can_be_preempted(&irq) {
panic!("`PeripheralMutex` cannot be created in an interrupt with higher priority than the interrupt it wraps");
panic!(
"`PeripheralMutex` cannot be created in an interrupt with higher priority than the interrupt it wraps"
);
}
let state_ptr = storage.0.as_mut_ptr();

View file

@ -1,6 +1,6 @@
use core::future::Future;
use embedded_hal_02::blocking;
use embedded_hal_02::serial;
use embedded_hal_02::{blocking, serial};
/// BlockingAsync is a wrapper that implements async traits using blocking peripherals. This allows
/// driver writers to depend on the async traits while still supporting embedded-hal peripheral implementations.
@ -25,9 +25,7 @@ impl<T> BlockingAsync<T> {
impl<T, E> embedded_hal_1::i2c::ErrorType for BlockingAsync<T>
where
E: embedded_hal_1::i2c::Error + 'static,
T: blocking::i2c::WriteRead<Error = E>
+ blocking::i2c::Read<Error = E>
+ blocking::i2c::Write<Error = E>,
T: blocking::i2c::WriteRead<Error = E> + blocking::i2c::Read<Error = E> + blocking::i2c::Write<Error = E>,
{
type Error = E;
}
@ -35,9 +33,7 @@ where
impl<T, E> embedded_hal_async::i2c::I2c for BlockingAsync<T>
where
E: embedded_hal_1::i2c::Error + 'static,
T: blocking::i2c::WriteRead<Error = E>
+ blocking::i2c::Read<Error = E>
+ blocking::i2c::Write<Error = E>,
T: blocking::i2c::WriteRead<Error = E> + blocking::i2c::Read<Error = E> + blocking::i2c::Write<Error = E>,
{
type WriteFuture<'a> = impl Future<Output = Result<(), Self::Error>> + 'a where Self: 'a;
type ReadFuture<'a> = impl Future<Output = Result<(), Self::Error>> + 'a where Self: 'a;
@ -51,12 +47,7 @@ where
async move { self.wrapped.write(address, bytes) }
}
fn write_read<'a>(
&'a mut self,
address: u8,
bytes: &'a [u8],
buffer: &'a mut [u8],
) -> Self::WriteReadFuture<'a> {
fn write_read<'a>(&'a mut self, address: u8, bytes: &'a [u8], buffer: &'a mut [u8]) -> Self::WriteReadFuture<'a> {
async move { self.wrapped.write_read(address, bytes, buffer) }
}

View file

@ -22,7 +22,9 @@
//! let i2c_dev2 = I2cBusDevice::new(i2c_bus);
//! let mpu = Mpu6050::new(i2c_dev2);
//! ```
use core::{fmt::Debug, future::Future};
use core::fmt::Debug;
use core::future::Future;
use embassy::blocking_mutex::raw::RawMutex;
use embassy::mutex::Mutex;
use embedded_hal_async::i2c;
@ -70,9 +72,7 @@ where
fn read<'a>(&'a mut self, address: u8, buffer: &'a mut [u8]) -> Self::ReadFuture<'a> {
async move {
let mut bus = self.bus.lock().await;
bus.read(address, buffer)
.await
.map_err(I2cBusDeviceError::I2c)?;
bus.read(address, buffer).await.map_err(I2cBusDeviceError::I2c)?;
Ok(())
}
}
@ -82,9 +82,7 @@ where
fn write<'a>(&'a mut self, address: u8, bytes: &'a [u8]) -> Self::WriteFuture<'a> {
async move {
let mut bus = self.bus.lock().await;
bus.write(address, bytes)
.await
.map_err(I2cBusDeviceError::I2c)?;
bus.write(address, bytes).await.map_err(I2cBusDeviceError::I2c)?;
Ok(())
}
}

View file

@ -25,10 +25,11 @@
//! let spi_dev2 = SpiBusDevice::new(spi_bus, cs_pin2);
//! let display2 = ST7735::new(spi_dev2, dc2, rst2, Default::default(), 160, 128);
//! ```
use core::{fmt::Debug, future::Future};
use core::fmt::Debug;
use core::future::Future;
use embassy::blocking_mutex::raw::RawMutex;
use embassy::mutex::Mutex;
use embedded_hal_1::digital::blocking::OutputPin;
use embedded_hal_1::spi::ErrorType;
use embedded_hal_async::spi;

View file

@ -7,9 +7,7 @@ pub struct OnDrop<F: FnOnce()> {
impl<F: FnOnce()> OnDrop<F> {
pub fn new(f: F) -> Self {
Self {
f: MaybeUninit::new(f),
}
Self { f: MaybeUninit::new(f) }
}
pub fn defuse(self) {

View file

@ -1,4 +1,5 @@
use core::ops::{Add, Div, Mul};
use num_traits::{CheckedAdd, CheckedDiv, CheckedMul};
/// Represents the ratio between two numbers.

View file

@ -1,25 +1,20 @@
//! A radio driver integration for the radio found on STM32WL family devices.
use core::future::Future;
use core::mem::MaybeUninit;
use embassy::channel::signal::Signal;
use embassy_hal_common::unborrow;
use embassy_stm32::interrupt::InterruptExt;
use embassy_stm32::dma::NoDma;
use embassy_stm32::gpio::{AnyPin, Output};
use embassy_stm32::interrupt::{InterruptExt, SUBGHZ_RADIO};
use embassy_stm32::subghz::{
CalibrateImage, CfgIrq, CodingRate, HeaderType, Irq, LoRaBandwidth, LoRaModParams, LoRaPacketParams, LoRaSyncWord,
Ocp, PaConfig, PaSel, PacketType, RampTime, RegMode, RfFreq, SpreadingFactor as SF, StandbyClk, Status, SubGhz,
TcxoMode, TcxoTrim, Timeout, TxParams,
};
use embassy_stm32::Unborrow;
use embassy_stm32::{
dma::NoDma,
gpio::{AnyPin, Output},
interrupt::SUBGHZ_RADIO,
subghz::{
CalibrateImage, CfgIrq, CodingRate, HeaderType, Irq, LoRaBandwidth, LoRaModParams,
LoRaPacketParams, LoRaSyncWord, Ocp, PaConfig, PaSel, PacketType, RampTime, RegMode,
RfFreq, SpreadingFactor as SF, StandbyClk, Status, SubGhz, TcxoMode, TcxoTrim, Timeout,
TxParams,
},
};
use lorawan_device::async_device::{
radio::{Bandwidth, PhyRxTx, RfConfig, RxQuality, SpreadingFactor, TxConfig},
Timings,
};
use lorawan_device::async_device::radio::{Bandwidth, PhyRxTx, RfConfig, RxQuality, SpreadingFactor, TxConfig};
use lorawan_device::async_device::Timings;
#[derive(Debug, Copy, Clone)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
@ -98,9 +93,7 @@ impl<'a> StateInner<'a> {
self.radio.set_standby(StandbyClk::Rc)?;
let tcxo_mode = TcxoMode::new()
.set_txco_trim(TcxoTrim::Volts1pt7)
.set_timeout(Timeout::from_duration_sat(
core::time::Duration::from_millis(40),
));
.set_timeout(Timeout::from_duration_sat(core::time::Duration::from_millis(40)));
self.radio.set_tcxo_mode(&tcxo_mode)?;
self.radio.set_regulator_mode(RegMode::Ldo)?;
@ -109,21 +102,14 @@ impl<'a> StateInner<'a> {
self.radio.set_buffer_base_address(0, 0)?;
self.radio.set_pa_config(
&PaConfig::new()
.set_pa_duty_cycle(0x1)
.set_hp_max(0x0)
.set_pa(PaSel::Lp),
)?;
self.radio
.set_pa_config(&PaConfig::new().set_pa_duty_cycle(0x1).set_hp_max(0x0).set_pa(PaSel::Lp))?;
self.radio.set_pa_ocp(Ocp::Max140m)?;
// let tx_params = TxParams::LP_14.set_ramp_time(RampTime::Micros40);
self.radio.set_tx_params(
&TxParams::new()
.set_ramp_time(RampTime::Micros40)
.set_power(0x0A),
)?;
self.radio
.set_tx_params(&TxParams::new().set_ramp_time(RampTime::Micros40).set_power(0x0A))?;
self.radio.set_packet_type(PacketType::LoRa)?;
self.radio.set_lora_sync_word(LoRaSyncWord::Public)?;
@ -193,19 +179,14 @@ impl<'a> StateInner<'a> {
/// Perform a radio receive operation with the radio config and receive buffer. The receive buffer must
/// be able to hold a single LoRaWAN packet.
async fn do_rx(
&mut self,
config: RfConfig,
buf: &mut [u8],
) -> Result<(usize, RxQuality), RadioError> {
async fn do_rx(&mut self, config: RfConfig, buf: &mut [u8]) -> Result<(usize, RxQuality), RadioError> {
assert!(buf.len() >= 255);
trace!("RX START");
// trace!("Starting RX: {}", config);
self.switch.set_rx();
self.configure()?;
self.radio
.set_rf_frequency(&RfFreq::from_frequency(config.frequency))?;
self.radio.set_rf_frequency(&RfFreq::from_frequency(config.frequency))?;
let mod_params = LoRaModParams::new()
.set_sf(convert_spreading_factor(config.spreading_factor))
@ -315,16 +296,8 @@ pub struct RadioSwitch<'a> {
}
impl<'a> RadioSwitch<'a> {
pub fn new(
ctrl1: Output<'a, AnyPin>,
ctrl2: Output<'a, AnyPin>,
ctrl3: Output<'a, AnyPin>,
) -> Self {
Self {
ctrl1,
ctrl2,
ctrl3,
}
pub fn new(ctrl1: Output<'a, AnyPin>, ctrl2: Output<'a, AnyPin>, ctrl3: Output<'a, AnyPin>) -> Self {
Self { ctrl1, ctrl2, ctrl3 }
}
pub(crate) fn set_rx(&mut self) {

View file

@ -1,11 +1,10 @@
use core::future::Future;
use embedded_hal::digital::v2::OutputPin;
use embedded_hal_async::digital::Wait;
use embedded_hal_async::spi::*;
use lorawan_device::async_device::{
radio::{Bandwidth, PhyRxTx, RfConfig, RxQuality, SpreadingFactor, TxConfig},
Timings,
};
use lorawan_device::async_device::radio::{Bandwidth, PhyRxTx, RfConfig, RxQuality, SpreadingFactor, TxConfig};
use lorawan_device::async_device::Timings;
mod sx127x_lora;
use sx127x_lora::{Error as RadioError, LoRa, RadioMode, IRQ};

View file

@ -11,9 +11,8 @@ use embedded_hal::digital::v2::OutputPin;
use embedded_hal_async::spi::SpiBus;
mod register;
use self::register::PaConfig;
use self::register::Register;
pub use self::register::IRQ;
use self::register::{PaConfig, Register};
/// Provides high-level access to Semtech SX1276/77/78/79 based boards connected to a Raspberry Pi
pub struct LoRa<SPI, CS, RESET> {
@ -72,15 +71,11 @@ where
let version = self.read_register(Register::RegVersion.addr()).await?;
if version == VERSION_CHECK {
self.set_mode(RadioMode::Sleep).await?;
self.write_register(Register::RegFifoTxBaseAddr.addr(), 0)
.await?;
self.write_register(Register::RegFifoRxBaseAddr.addr(), 0)
.await?;
self.write_register(Register::RegFifoTxBaseAddr.addr(), 0).await?;
self.write_register(Register::RegFifoRxBaseAddr.addr(), 0).await?;
let lna = self.read_register(Register::RegLna.addr()).await?;
self.write_register(Register::RegLna.addr(), lna | 0x03)
.await?;
self.write_register(Register::RegModemConfig3.addr(), 0x04)
.await?;
self.write_register(Register::RegLna.addr(), lna | 0x03).await?;
self.write_register(Register::RegModemConfig3.addr(), 0x04).await?;
self.set_tcxo(true).await?;
self.set_mode(RadioMode::Stdby).await?;
self.cs.set_high().map_err(CS)?;
@ -106,10 +101,7 @@ where
.await
}
pub async fn transmit_start(
&mut self,
buffer: &[u8],
) -> Result<(), Error<E, CS::Error, RESET::Error>> {
pub async fn transmit_start(&mut self, buffer: &[u8]) -> Result<(), Error<E, CS::Error, RESET::Error>> {
assert!(buffer.len() < 255);
if self.transmitting().await? {
//trace!("ALREADY TRANSMNITTING");
@ -123,10 +115,8 @@ where
}
self.write_register(Register::RegIrqFlags.addr(), 0).await?;
self.write_register(Register::RegFifoAddrPtr.addr(), 0)
.await?;
self.write_register(Register::RegPayloadLength.addr(), 0)
.await?;
self.write_register(Register::RegFifoAddrPtr.addr(), 0).await?;
self.write_register(Register::RegPayloadLength.addr(), 0).await?;
for byte in buffer.iter() {
self.write_register(Register::RegFifo.addr(), *byte).await?;
}
@ -138,10 +128,7 @@ where
}
pub async fn packet_ready(&mut self) -> Result<bool, Error<E, CS::Error, RESET::Error>> {
Ok(self
.read_register(Register::RegIrqFlags.addr())
.await?
.get_bit(6))
Ok(self.read_register(Register::RegIrqFlags.addr()).await?.get_bit(6))
}
pub async fn irq_flags_mask(&mut self) -> Result<u8, Error<E, CS::Error, RESET::Error>> {
@ -159,37 +146,26 @@ where
/// Returns the contents of the fifo as a fixed 255 u8 array. This should only be called is there is a
/// new packet ready to be read.
pub async fn read_packet(
&mut self,
buffer: &mut [u8],
) -> Result<(), Error<E, CS::Error, RESET::Error>> {
pub async fn read_packet(&mut self, buffer: &mut [u8]) -> Result<(), Error<E, CS::Error, RESET::Error>> {
self.clear_irq().await?;
let size = self.read_register(Register::RegRxNbBytes.addr()).await?;
assert!(size as usize <= buffer.len());
let fifo_addr = self
.read_register(Register::RegFifoRxCurrentAddr.addr())
.await?;
self.write_register(Register::RegFifoAddrPtr.addr(), fifo_addr)
.await?;
let fifo_addr = self.read_register(Register::RegFifoRxCurrentAddr.addr()).await?;
self.write_register(Register::RegFifoAddrPtr.addr(), fifo_addr).await?;
for i in 0..size {
let byte = self.read_register(Register::RegFifo.addr()).await?;
buffer[i as usize] = byte;
}
self.write_register(Register::RegFifoAddrPtr.addr(), 0)
.await?;
self.write_register(Register::RegFifoAddrPtr.addr(), 0).await?;
Ok(())
}
/// Returns true if the radio is currently transmitting a packet.
pub async fn transmitting(&mut self) -> Result<bool, Error<E, CS::Error, RESET::Error>> {
if (self.read_register(Register::RegOpMode.addr()).await?) & RadioMode::Tx.addr()
== RadioMode::Tx.addr()
{
if (self.read_register(Register::RegOpMode.addr()).await?) & RadioMode::Tx.addr() == RadioMode::Tx.addr() {
Ok(true)
} else {
if (self.read_register(Register::RegIrqFlags.addr()).await? & IRQ::IrqTxDoneMask.addr())
== 1
{
if (self.read_register(Register::RegIrqFlags.addr()).await? & IRQ::IrqTxDoneMask.addr()) == 1 {
self.write_register(Register::RegIrqFlags.addr(), IRQ::IrqTxDoneMask.addr())
.await?;
}
@ -200,8 +176,7 @@ where
/// Clears the radio's IRQ registers.
pub async fn clear_irq(&mut self) -> Result<u8, Error<E, CS::Error, RESET::Error>> {
let irq_flags = self.read_register(Register::RegIrqFlags.addr()).await?;
self.write_register(Register::RegIrqFlags.addr(), 0xFF)
.await?;
self.write_register(Register::RegIrqFlags.addr(), 0xFF).await?;
Ok(irq_flags)
}
@ -243,11 +218,8 @@ where
self.set_ocp(100).await?;
}
level -= 2;
self.write_register(
Register::RegPaConfig.addr(),
PaConfig::PaBoost.addr() | level as u8,
)
.await
self.write_register(Register::RegPaConfig.addr(), PaConfig::PaBoost.addr() | level as u8)
.await
}
}
@ -269,10 +241,7 @@ where
}
/// Sets the state of the radio. Default mode after initiation is `Standby`.
pub async fn set_mode(
&mut self,
mode: RadioMode,
) -> Result<(), Error<E, CS::Error, RESET::Error>> {
pub async fn set_mode(&mut self, mode: RadioMode) -> Result<(), Error<E, CS::Error, RESET::Error>> {
if self.explicit_header {
self.set_explicit_header_mode().await?;
} else {
@ -289,25 +258,18 @@ where
}
pub async fn reset_payload_length(&mut self) -> Result<(), Error<E, CS::Error, RESET::Error>> {
self.write_register(Register::RegPayloadLength.addr(), 0xFF)
.await
self.write_register(Register::RegPayloadLength.addr(), 0xFF).await
}
/// Sets the frequency of the radio. Values are in megahertz.
/// I.E. 915 MHz must be used for North America. Check regulation for your area.
pub async fn set_frequency(
&mut self,
freq: u32,
) -> Result<(), Error<E, CS::Error, RESET::Error>> {
pub async fn set_frequency(&mut self, freq: u32) -> Result<(), Error<E, CS::Error, RESET::Error>> {
const FREQ_STEP: f64 = 61.03515625;
// calculate register values
let frf = (freq as f64 / FREQ_STEP) as u32;
// write registers
self.write_register(
Register::RegFrfMsb.addr(),
((frf & 0x00FF_0000) >> 16) as u8,
)
.await?;
self.write_register(Register::RegFrfMsb.addr(), ((frf & 0x00FF_0000) >> 16) as u8)
.await?;
self.write_register(Register::RegFrfMid.addr(), ((frf & 0x0000_FF00) >> 8) as u8)
.await?;
self.write_register(Register::RegFrfLsb.addr(), (frf & 0x0000_00FF) as u8)
@ -335,10 +297,7 @@ where
/// Sets the spreading factor of the radio. Supported values are between 6 and 12.
/// If a spreading factor of 6 is set, implicit header mode must be used to transmit
/// and receive packets. Default value is `7`.
pub async fn set_spreading_factor(
&mut self,
mut sf: u8,
) -> Result<(), Error<E, CS::Error, RESET::Error>> {
pub async fn set_spreading_factor(&mut self, mut sf: u8) -> Result<(), Error<E, CS::Error, RESET::Error>> {
if sf < 6 {
sf = 6;
} else if sf > 12 {
@ -346,13 +305,11 @@ where
}
if sf == 6 {
self.write_register(Register::RegDetectionOptimize.addr(), 0xc5)
.await?;
self.write_register(Register::RegDetectionOptimize.addr(), 0xc5).await?;
self.write_register(Register::RegDetectionThreshold.addr(), 0x0c)
.await?;
} else {
self.write_register(Register::RegDetectionOptimize.addr(), 0xc3)
.await?;
self.write_register(Register::RegDetectionOptimize.addr(), 0xc3).await?;
self.write_register(Register::RegDetectionThreshold.addr(), 0x0a)
.await?;
}
@ -364,16 +321,12 @@ where
.await?;
self.set_ldo_flag().await?;
self.write_register(Register::RegSymbTimeoutLsb.addr(), 0x05)
.await?;
self.write_register(Register::RegSymbTimeoutLsb.addr(), 0x05).await?;
Ok(())
}
pub async fn set_tcxo(
&mut self,
external: bool,
) -> Result<(), Error<E, CS::Error, RESET::Error>> {
pub async fn set_tcxo(&mut self, external: bool) -> Result<(), Error<E, CS::Error, RESET::Error>> {
if external {
self.write_register(Register::RegTcxo.addr(), 0x10).await
} else {
@ -384,10 +337,7 @@ where
/// Sets the signal bandwidth of the radio. Supported values are: `7800 Hz`, `10400 Hz`,
/// `15600 Hz`, `20800 Hz`, `31250 Hz`,`41700 Hz` ,`62500 Hz`,`125000 Hz` and `250000 Hz`
/// Default value is `125000 Hz`
pub async fn set_signal_bandwidth(
&mut self,
sbw: i64,
) -> Result<(), Error<E, CS::Error, RESET::Error>> {
pub async fn set_signal_bandwidth(&mut self, sbw: i64) -> Result<(), Error<E, CS::Error, RESET::Error>> {
let bw: i64 = match sbw {
7_800 => 0,
10_400 => 1,
@ -413,10 +363,7 @@ where
/// Sets the coding rate of the radio with the numerator fixed at 4. Supported values
/// are between `5` and `8`, these correspond to coding rates of `4/5` and `4/8`.
/// Default value is `5`.
pub async fn set_coding_rate_4(
&mut self,
mut denominator: u8,
) -> Result<(), Error<E, CS::Error, RESET::Error>> {
pub async fn set_coding_rate_4(&mut self, mut denominator: u8) -> Result<(), Error<E, CS::Error, RESET::Error>> {
if denominator < 5 {
denominator = 5;
} else if denominator > 8 {
@ -424,23 +371,16 @@ where
}
let cr = denominator - 4;
let modem_config_1 = self.read_register(Register::RegModemConfig1.addr()).await?;
self.write_register(
Register::RegModemConfig1.addr(),
(modem_config_1 & 0xf1) | (cr << 1),
)
.await
self.write_register(Register::RegModemConfig1.addr(), (modem_config_1 & 0xf1) | (cr << 1))
.await
}
/// Sets the preamble length of the radio. Values are between 6 and 65535.
/// Default value is `8`.
pub async fn set_preamble_length(
&mut self,
length: i64,
) -> Result<(), Error<E, CS::Error, RESET::Error>> {
pub async fn set_preamble_length(&mut self, length: i64) -> Result<(), Error<E, CS::Error, RESET::Error>> {
self.write_register(Register::RegPreambleMsb.addr(), (length >> 8) as u8)
.await?;
self.write_register(Register::RegPreambleLsb.addr(), length as u8)
.await
self.write_register(Register::RegPreambleLsb.addr(), length as u8).await
}
/// Enables are disables the radio's CRC check. Default value is `false`.
@ -456,20 +396,13 @@ where
}
/// Inverts the radio's IQ signals. Default value is `false`.
pub async fn set_invert_iq(
&mut self,
value: bool,
) -> Result<(), Error<E, CS::Error, RESET::Error>> {
pub async fn set_invert_iq(&mut self, value: bool) -> Result<(), Error<E, CS::Error, RESET::Error>> {
if value {
self.write_register(Register::RegInvertiq.addr(), 0x66)
.await?;
self.write_register(Register::RegInvertiq2.addr(), 0x19)
.await
self.write_register(Register::RegInvertiq.addr(), 0x66).await?;
self.write_register(Register::RegInvertiq2.addr(), 0x19).await
} else {
self.write_register(Register::RegInvertiq.addr(), 0x27)
.await?;
self.write_register(Register::RegInvertiq2.addr(), 0x1d)
.await
self.write_register(Register::RegInvertiq.addr(), 0x27).await?;
self.write_register(Register::RegInvertiq2.addr(), 0x1d).await
}
}
@ -504,15 +437,11 @@ where
/// Returns the signal to noise radio of the the last received packet.
pub async fn get_packet_snr(&mut self) -> Result<f64, Error<E, CS::Error, RESET::Error>> {
Ok(f64::from(
self.read_register(Register::RegPktSnrValue.addr()).await?,
))
Ok(f64::from(self.read_register(Register::RegPktSnrValue.addr()).await?))
}
/// Returns the frequency error of the last received packet in Hz.
pub async fn get_packet_frequency_error(
&mut self,
) -> Result<i64, Error<E, CS::Error, RESET::Error>> {
pub async fn get_packet_frequency_error(&mut self) -> Result<i64, Error<E, CS::Error, RESET::Error>> {
let mut freq_error: i32;
freq_error = i32::from(self.read_register(Register::RegFreqErrorMsb.addr()).await? & 0x7);
freq_error <<= 8i64;
@ -537,29 +466,20 @@ where
let mut config_3 = self.read_register(Register::RegModemConfig3.addr()).await?;
config_3.set_bit(3, ldo_on);
//config_3.set_bit(2, true);
self.write_register(Register::RegModemConfig3.addr(), config_3)
.await
self.write_register(Register::RegModemConfig3.addr(), config_3).await
}
async fn read_register(&mut self, reg: u8) -> Result<u8, Error<E, CS::Error, RESET::Error>> {
let mut buffer = [reg & 0x7f, 0];
self.cs.set_low().map_err(CS)?;
let _ = self
.spi
.transfer(&mut buffer, &[reg & 0x7f, 0])
.await
.map_err(SPI)?;
let _ = self.spi.transfer(&mut buffer, &[reg & 0x7f, 0]).await.map_err(SPI)?;
self.cs.set_high().map_err(CS)?;
Ok(buffer[1])
}
async fn write_register(
&mut self,
reg: u8,
byte: u8,
) -> Result<(), Error<E, CS::Error, RESET::Error>> {
async fn write_register(&mut self, reg: u8, byte: u8) -> Result<(), Error<E, CS::Error, RESET::Error>> {
self.cs.set_low().map_err(CS)?;
let buffer = [reg | 0x80, byte];
self.spi.write(&buffer).await.map_err(SPI)?;
@ -576,8 +496,7 @@ where
.set_bit(3, false) //Low freq registers
.set_bits(0..2, 0b011); // Mode
self.write_register(Register::RegOpMode as u8, op_mode)
.await
self.write_register(Register::RegOpMode as u8, op_mode).await
}
pub async fn set_fsk_pa_ramp(
@ -590,8 +509,7 @@ where
.set_bits(5..6, modulation_shaping as u8)
.set_bits(0..3, ramp as u8);
self.write_register(Register::RegPaRamp as u8, pa_ramp)
.await
self.write_register(Register::RegPaRamp as u8, pa_ramp).await
}
pub async fn set_lora_pa_ramp(&mut self) -> Result<(), Error<E, CS::Error, RESET::Error>> {

View file

@ -25,17 +25,13 @@ pub fn main(args: TokenStream, item: TokenStream) -> TokenStream {
pub fn cortex_m_interrupt(args: TokenStream, item: TokenStream) -> TokenStream {
let args = syn::parse_macro_input!(args as syn::AttributeArgs);
let f = syn::parse_macro_input!(item as syn::ItemFn);
cortex_m_interrupt::run(args, f)
.unwrap_or_else(|x| x)
.into()
cortex_m_interrupt::run(args, f).unwrap_or_else(|x| x).into()
}
#[proc_macro]
pub fn cortex_m_interrupt_declare(item: TokenStream) -> TokenStream {
let name = syn::parse_macro_input!(item as syn::Ident);
cortex_m_interrupt_declare::run(name)
.unwrap_or_else(|x| x)
.into()
cortex_m_interrupt_declare::run(name).unwrap_or_else(|x| x).into()
}
/// # interrupt_take procedural macro
@ -46,7 +42,5 @@ pub fn cortex_m_interrupt_declare(item: TokenStream) -> TokenStream {
#[proc_macro]
pub fn cortex_m_interrupt_take(item: TokenStream) -> TokenStream {
let name = syn::parse_macro_input!(item as syn::Ident);
cortex_m_interrupt_take::run(name)
.unwrap_or_else(|x| x)
.into()
cortex_m_interrupt_take::run(name).unwrap_or_else(|x| x).into()
}

View file

@ -1,9 +1,9 @@
use std::iter;
use darling::FromMeta;
use proc_macro2::TokenStream;
use quote::quote;
use std::iter;
use syn::ReturnType;
use syn::{Type, Visibility};
use syn::{ReturnType, Type, Visibility};
use crate::util::ctxt::Ctxt;

View file

@ -81,14 +81,11 @@ pub fn run(args: syn::AttributeArgs, f: syn::ItemFn) -> Result<TokenStream, Toke
#[cfg(all(not(feature = "std"), not(feature = "wasm")))]
let main = {
let config = args
.config
.map(|s| s.parse::<syn::Expr>().unwrap())
.unwrap_or_else(|| {
syn::Expr::Verbatim(quote! {
Default::default()
})
});
let config = args.config.map(|s| s.parse::<syn::Expr>().unwrap()).unwrap_or_else(|| {
syn::Expr::Verbatim(quote! {
Default::default()
})
});
let (hal_setup, peris_arg) = match HAL {
Some(hal) => {

View file

@ -47,10 +47,7 @@ pub fn run(args: syn::AttributeArgs, f: syn::ItemFn) -> Result<TokenStream, Toke
id.mutability = None;
}
_ => {
ctxt.error_spanned_by(
arg,
"pattern matching in task arguments is not yet supported",
);
ctxt.error_spanned_by(arg, "pattern matching in task arguments is not yet supported");
}
},
}

View file

@ -1,11 +1,12 @@
// nifty utility borrowed from serde :)
// https://github.com/serde-rs/serde/blob/master/serde_derive/src/internals/ctxt.rs
use proc_macro2::TokenStream;
use quote::{quote, ToTokens};
use std::cell::RefCell;
use std::fmt::Display;
use std::thread;
use proc_macro2::TokenStream;
use quote::{quote, ToTokens};
use syn;
/// A type to collect errors together and format them.

View file

@ -1,6 +1,6 @@
use core::task::Waker;
use smoltcp::phy::Device as SmolDevice;
use smoltcp::phy::DeviceCapabilities;
use smoltcp::phy::{Device as SmolDevice, DeviceCapabilities};
use smoltcp::time::Instant as SmolInstant;
use crate::packet_pool::PacketBoxExt;

View file

@ -18,11 +18,9 @@ pub mod tcp;
// smoltcp reexports
pub use smoltcp::phy::{DeviceCapabilities, Medium};
pub use smoltcp::time::Duration as SmolDuration;
pub use smoltcp::time::Instant as SmolInstant;
pub use smoltcp::time::{Duration as SmolDuration, Instant as SmolInstant};
#[cfg(feature = "medium-ethernet")]
pub use smoltcp::wire::{EthernetAddress, HardwareAddress};
pub use smoltcp::wire::{IpAddress, IpCidr, Ipv4Address, Ipv4Cidr};
#[cfg(feature = "proto-ipv6")]
pub use smoltcp::wire::{Ipv6Address, Ipv6Cidr};

View file

@ -1,6 +1,6 @@
use as_slice::{AsMutSlice, AsSlice};
use core::ops::{Deref, DerefMut, Range};
use as_slice::{AsMutSlice, AsSlice};
use atomic_pool::{pool, Box};
pub const MTU: usize = 1516;
@ -41,10 +41,7 @@ pub trait PacketBoxExt {
impl PacketBoxExt for PacketBox {
fn slice(self, range: Range<usize>) -> PacketBuf {
PacketBuf {
packet: self,
range,
}
PacketBuf { packet: self, range }
}
}

View file

@ -1,7 +1,7 @@
use core::cell::UnsafeCell;
use core::future::Future;
use core::task::Context;
use core::task::Poll;
use core::task::{Context, Poll};
use embassy::time::{Instant, Timer};
use embassy::waitqueue::WakerRegistration;
use futures::future::poll_fn;
@ -9,19 +9,17 @@ use futures::pin_mut;
use heapless::Vec;
#[cfg(feature = "dhcpv4")]
use smoltcp::iface::SocketHandle;
use smoltcp::iface::{Interface, InterfaceBuilder};
use smoltcp::iface::{SocketSet, SocketStorage};
#[cfg(feature = "dhcpv4")]
use smoltcp::socket::dhcpv4;
use smoltcp::time::Instant as SmolInstant;
use smoltcp::wire::{IpCidr, Ipv4Address, Ipv4Cidr};
use smoltcp::iface::{Interface, InterfaceBuilder, SocketSet, SocketStorage};
#[cfg(feature = "medium-ethernet")]
use smoltcp::iface::{Neighbor, NeighborCache, Route, Routes};
#[cfg(feature = "medium-ethernet")]
use smoltcp::phy::{Device as _, Medium};
#[cfg(feature = "dhcpv4")]
use smoltcp::socket::dhcpv4;
use smoltcp::time::Instant as SmolInstant;
#[cfg(feature = "medium-ethernet")]
use smoltcp::wire::{EthernetAddress, HardwareAddress, IpAddress};
use smoltcp::wire::{IpCidr, Ipv4Address, Ipv4Cidr};
use crate::device::{Device, DeviceAdapter, LinkState};
@ -38,9 +36,7 @@ pub struct StackResources<const ADDR: usize, const SOCK: usize, const NEIGHBOR:
neighbor_cache: [Option<(IpAddress, Neighbor)>; NEIGHBOR],
}
impl<const ADDR: usize, const SOCK: usize, const NEIGHBOR: usize>
StackResources<ADDR, SOCK, NEIGHBOR>
{
impl<const ADDR: usize, const SOCK: usize, const NEIGHBOR: usize> StackResources<ADDR, SOCK, NEIGHBOR> {
pub fn new() -> Self {
Self {
addresses: [IpCidr::new(Ipv4Address::UNSPECIFIED.into(), 32); ADDR],
@ -122,8 +118,7 @@ impl<D: Device + 'static> Stack<D> {
let sockets = SocketSet::new(&mut resources.sockets[..]);
let next_local_port =
(random_seed % (LOCAL_PORT_MAX - LOCAL_PORT_MIN) as u64) as u16 + LOCAL_PORT_MIN;
let next_local_port = (random_seed % (LOCAL_PORT_MAX - LOCAL_PORT_MIN) as u64) as u16 + LOCAL_PORT_MIN;
let mut inner = Inner {
device,
@ -194,11 +189,7 @@ impl SocketStack {
#[allow(clippy::absurd_extreme_comparisons)]
pub fn get_local_port(&mut self) -> u16 {
let res = self.next_local_port;
self.next_local_port = if res >= LOCAL_PORT_MAX {
LOCAL_PORT_MIN
} else {
res + 1
};
self.next_local_port = if res >= LOCAL_PORT_MAX { LOCAL_PORT_MIN } else { res + 1 };
res
}
}
@ -217,10 +208,7 @@ impl<D: Device + 'static> Inner<D> {
if medium == Medium::Ethernet {
if let Some(gateway) = config.gateway {
debug!(" Default gateway: {}", gateway);
s.iface
.routes_mut()
.add_default_ipv4_route(gateway)
.unwrap();
s.iface.routes_mut().add_default_ipv4_route(gateway).unwrap();
} else {
debug!(" Default gateway: None");
s.iface.routes_mut().remove_default_ipv4_route();
@ -259,10 +247,7 @@ impl<D: Device + 'static> Inner<D> {
s.waker.register(cx.waker());
let timestamp = instant_to_smoltcp(Instant::now());
if s.iface
.poll(timestamp, &mut self.device, &mut s.sockets)
.is_err()
{
if s.iface.poll(timestamp, &mut self.device, &mut s.sockets).is_err() {
// If poll() returns error, it may not be done yet, so poll again later.
cx.waker().wake_by_ref();
return;

View file

@ -2,17 +2,16 @@ use core::cell::UnsafeCell;
use core::future::Future;
use core::mem;
use core::task::Poll;
use futures::future::poll_fn;
use smoltcp::iface::{Interface, SocketHandle};
use smoltcp::socket::tcp;
use smoltcp::time::Duration;
use smoltcp::wire::IpEndpoint;
use smoltcp::wire::IpListenEndpoint;
use crate::stack::SocketStack;
use crate::Device;
use smoltcp::wire::{IpEndpoint, IpListenEndpoint};
use super::stack::Stack;
use crate::stack::SocketStack;
use crate::Device;
#[derive(PartialEq, Eq, Clone, Copy, Debug)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
@ -57,11 +56,7 @@ pub struct TcpWriter<'a> {
}
impl<'a> TcpSocket<'a> {
pub fn new<D: Device>(
stack: &'a Stack<D>,
rx_buffer: &'a mut [u8],
tx_buffer: &'a mut [u8],
) -> Self {
pub fn new<D: Device>(stack: &'a Stack<D>, rx_buffer: &'a mut [u8], tx_buffer: &'a mut [u8]) -> Self {
// safety: not accessed reentrantly.
let s = unsafe { &mut *stack.socket.get() };
let rx_buffer: &'static mut [u8] = unsafe { mem::transmute(rx_buffer) };
@ -91,10 +86,7 @@ impl<'a> TcpSocket<'a> {
let local_port = unsafe { &mut *self.io.stack.get() }.get_local_port();
// safety: not accessed reentrantly.
match unsafe {
self.io
.with_mut(|s, i| s.connect(i, remote_endpoint, local_port))
} {
match unsafe { self.io.with_mut(|s, i| s.connect(i, remote_endpoint, local_port)) } {
Ok(()) => {}
Err(tcp::ConnectError::InvalidState) => return Err(ConnectError::InvalidState),
Err(tcp::ConnectError::Unaddressable) => return Err(ConnectError::NoRoute),
@ -102,9 +94,7 @@ impl<'a> TcpSocket<'a> {
futures::future::poll_fn(|cx| unsafe {
self.io.with_mut(|s, _| match s.state() {
tcp::State::Closed | tcp::State::TimeWait => {
Poll::Ready(Err(ConnectError::ConnectionReset))
}
tcp::State::Closed | tcp::State::TimeWait => Poll::Ready(Err(ConnectError::ConnectionReset)),
tcp::State::Listen => unreachable!(),
tcp::State::SynSent | tcp::State::SynReceived => {
s.register_send_waker(cx.waker());

View file

@ -13,29 +13,27 @@
//!
//! Please also see [crate::uarte] to understand when [BufferedUarte] should be used.
use crate::interrupt::InterruptExt;
use crate::Unborrow;
use core::cmp::min;
use core::future::Future;
use core::marker::PhantomData;
use core::sync::atomic::{compiler_fence, Ordering};
use core::task::Poll;
use embassy::waitqueue::WakerRegistration;
use embassy_cortex_m::peripheral::{PeripheralMutex, PeripheralState, StateStorage};
use embassy_hal_common::ring_buffer::RingBuffer;
use embassy_hal_common::{low_power_wait_until, unborrow};
use futures::future::poll_fn;
use crate::gpio::Pin as GpioPin;
use crate::pac;
use crate::ppi::{AnyConfigurableChannel, ConfigurableChannel, Event, Ppi, Task};
use crate::timer::Instance as TimerInstance;
use crate::timer::{Frequency, Timer};
use crate::uarte::{apply_workaround_for_enable_anomaly, Config, Instance as UarteInstance};
// Re-export SVD variants to allow user to directly set values
pub use pac::uarte0::{baudrate::BAUDRATE_A as Baudrate, config::PARITY_A as Parity};
use crate::gpio::Pin as GpioPin;
use crate::interrupt::InterruptExt;
use crate::ppi::{AnyConfigurableChannel, ConfigurableChannel, Event, Ppi, Task};
use crate::timer::{Frequency, Instance as TimerInstance, Timer};
use crate::uarte::{apply_workaround_for_enable_anomaly, Config, Instance as UarteInstance};
use crate::{pac, Unborrow};
#[derive(Copy, Clone, Debug, PartialEq)]
enum RxState {
Idle,
@ -234,9 +232,7 @@ impl<'d, U: UarteInstance, T: TimerInstance> embedded_io::asynch::Read for Buffe
}
}
impl<'d, U: UarteInstance, T: TimerInstance> embedded_io::asynch::BufRead
for BufferedUarte<'d, U, T>
{
impl<'d, U: UarteInstance, T: TimerInstance> embedded_io::asynch::BufRead for BufferedUarte<'d, U, T> {
type FillBufFuture<'a> = impl Future<Output = Result<&'a [u8], Self::Error>>
where
Self: 'a;
@ -276,9 +272,7 @@ impl<'d, U: UarteInstance, T: TimerInstance> embedded_io::asynch::BufRead
}
}
impl<'d, U: UarteInstance, T: TimerInstance> embedded_io::asynch::Write
for BufferedUarte<'d, U, T>
{
impl<'d, U: UarteInstance, T: TimerInstance> embedded_io::asynch::Write for BufferedUarte<'d, U, T> {
type WriteFuture<'a> = impl Future<Output = Result<usize, Self::Error>>
where
Self: 'a;

View file

@ -197,9 +197,10 @@ impl_saadc_input!(P0_04, ANALOGINPUT2);
impl_saadc_input!(P0_05, ANALOGINPUT3);
pub mod irqs {
use crate::pac::Interrupt as InterruptEnum;
use embassy_macros::cortex_m_interrupt_declare as declare;
use crate::pac::Interrupt as InterruptEnum;
declare!(POWER_CLOCK);
declare!(RADIO);
declare!(UARTE0_UART0);

View file

@ -218,9 +218,10 @@ impl_saadc_input!(P0_30, ANALOGINPUT6);
impl_saadc_input!(P0_31, ANALOGINPUT7);
pub mod irqs {
use crate::pac::Interrupt as InterruptEnum;
use embassy_macros::cortex_m_interrupt_declare as declare;
use crate::pac::Interrupt as InterruptEnum;
declare!(POWER_CLOCK);
declare!(RADIO);
declare!(UARTE0_UART0);

View file

@ -219,9 +219,10 @@ impl_saadc_input!(P0_30, ANALOGINPUT6);
impl_saadc_input!(P0_31, ANALOGINPUT7);
pub mod irqs {
use crate::pac::Interrupt as InterruptEnum;
use embassy_macros::cortex_m_interrupt_declare as declare;
use crate::pac::Interrupt as InterruptEnum;
declare!(POWER_CLOCK);
declare!(RADIO);
declare!(UARTE0_UART0);

View file

@ -211,9 +211,10 @@ impl_ppi_channel!(PPI_CH30, 30 => static);
impl_ppi_channel!(PPI_CH31, 31 => static);
pub mod irqs {
use crate::pac::Interrupt as InterruptEnum;
use embassy_macros::cortex_m_interrupt_declare as declare;
use crate::pac::Interrupt as InterruptEnum;
declare!(POWER_CLOCK);
declare!(RADIO);
declare!(UARTE0_UART0);

View file

@ -235,9 +235,10 @@ impl_saadc_input!(P0_30, ANALOGINPUT6);
impl_saadc_input!(P0_31, ANALOGINPUT7);
pub mod irqs {
use crate::pac::Interrupt as InterruptEnum;
use embassy_macros::cortex_m_interrupt_declare as declare;
use crate::pac::Interrupt as InterruptEnum;
declare!(POWER_CLOCK);
declare!(RADIO);
declare!(UARTE0_UART0);

View file

@ -278,9 +278,10 @@ impl_saadc_input!(P0_30, ANALOGINPUT6);
impl_saadc_input!(P0_31, ANALOGINPUT7);
pub mod irqs {
use crate::pac::Interrupt as InterruptEnum;
use embassy_macros::cortex_m_interrupt_declare as declare;
use crate::pac::Interrupt as InterruptEnum;
declare!(POWER_CLOCK);
declare!(RADIO);
declare!(UARTE0_UART0);

View file

@ -283,9 +283,10 @@ impl_saadc_input!(P0_30, ANALOGINPUT6);
impl_saadc_input!(P0_31, ANALOGINPUT7);
pub mod irqs {
use crate::pac::Interrupt as InterruptEnum;
use embassy_macros::cortex_m_interrupt_declare as declare;
use crate::pac::Interrupt as InterruptEnum;
declare!(POWER_CLOCK);
declare!(RADIO);
declare!(UARTE0_UART0);

View file

@ -468,9 +468,10 @@ impl_saadc_input!(P0_19, ANALOGINPUT6);
impl_saadc_input!(P0_20, ANALOGINPUT7);
pub mod irqs {
use crate::pac::Interrupt as InterruptEnum;
use embassy_macros::cortex_m_interrupt_declare as declare;
use crate::pac::Interrupt as InterruptEnum;
declare!(FPU);
declare!(CACHE);
declare!(SPU);

View file

@ -328,9 +328,10 @@ impl_ppi_channel!(PPI_CH30, 30 => configurable);
impl_ppi_channel!(PPI_CH31, 31 => configurable);
pub mod irqs {
use crate::pac::Interrupt as InterruptEnum;
use embassy_macros::cortex_m_interrupt_declare as declare;
use crate::pac::Interrupt as InterruptEnum;
declare!(CLOCK_POWER);
declare!(RADIO);
declare!(RNG);

View file

@ -346,9 +346,10 @@ impl_saadc_input!(P0_19, ANALOGINPUT6);
impl_saadc_input!(P0_20, ANALOGINPUT7);
pub mod irqs {
use crate::pac::Interrupt as InterruptEnum;
use embassy_macros::cortex_m_interrupt_declare as declare;
use crate::pac::Interrupt as InterruptEnum;
declare!(SPU);
declare!(CLOCK_POWER);
declare!(UARTE0_SPIM0_SPIS0_TWIM0_TWIS0);

View file

@ -4,15 +4,13 @@ use core::convert::Infallible;
use core::hint::unreachable_unchecked;
use core::marker::PhantomData;
use crate::Unborrow;
use cfg_if::cfg_if;
use embassy_hal_common::{unborrow, unsafe_impl_unborrow};
use crate::pac;
use self::sealed::Pin as _;
use crate::pac::p0 as gpio;
use crate::pac::p0::pin_cnf::{DRIVE_A, PULL_A};
use self::sealed::Pin as _;
use crate::{pac, Unborrow};
/// A GPIO port with up to 32 pins.
#[derive(Debug, Eq, PartialEq)]
@ -93,11 +91,7 @@ pub struct Output<'d, T: Pin> {
}
impl<'d, T: Pin> Output<'d, T> {
pub fn new(
pin: impl Unborrow<Target = T> + 'd,
initial_output: Level,
drive: OutputDrive,
) -> Self {
pub fn new(pin: impl Unborrow<Target = T> + 'd, initial_output: Level, drive: OutputDrive) -> Self {
let mut pin = Flex::new(pin);
match initial_output {
Level::High => pin.set_high(),

View file

@ -1,17 +1,17 @@
use crate::interrupt::{Interrupt, InterruptExt};
use core::convert::Infallible;
use core::future::Future;
use core::marker::PhantomData;
use core::task::{Context, Poll};
use embassy::waitqueue::AtomicWaker;
use embassy_hal_common::unsafe_impl_unborrow;
use futures::future::poll_fn;
use crate::gpio::sealed::Pin as _;
use crate::gpio::{AnyPin, Flex, Input, Output, Pin as GpioPin};
use crate::pac;
use crate::interrupt::{Interrupt, InterruptExt};
use crate::ppi::{Event, Task};
use crate::{interrupt, peripherals};
use crate::{interrupt, pac, peripherals};
pub const CHANNEL_COUNT: usize = 8;
@ -468,9 +468,7 @@ mod eh1 {
type Error = Infallible;
}
impl<'d, C: Channel, T: GpioPin> embedded_hal_1::digital::blocking::InputPin
for InputChannel<'d, C, T>
{
impl<'d, C: Channel, T: GpioPin> embedded_hal_1::digital::blocking::InputPin for InputChannel<'d, C, T> {
fn is_high(&self) -> Result<bool, Self::Error> {
Ok(self.pin.is_high())
}

View file

@ -35,10 +35,7 @@
//! mutable slices always reside in RAM.
#![no_std]
#![cfg_attr(
feature = "nightly",
feature(generic_associated_types, type_alias_impl_trait)
)]
#![cfg_attr(feature = "nightly", feature(generic_associated_types, type_alias_impl_trait))]
#[cfg(not(any(
feature = "nrf51",
@ -115,9 +112,10 @@ mod chip;
pub use chip::EASY_DMA_SIZE;
pub mod interrupt {
pub use crate::chip::irqs::*;
pub use cortex_m::interrupt::{CriticalSection, Mutex};
pub use embassy_cortex_m::interrupt::*;
pub use crate::chip::irqs::*;
}
// Reexports
@ -126,7 +124,6 @@ pub mod interrupt {
pub use chip::pac;
#[cfg(not(feature = "unstable-pac"))]
pub(crate) use chip::pac;
pub use chip::{peripherals, Peripherals};
pub use embassy_cortex_m::executor;
pub use embassy_hal_common::{unborrow, Unborrow};

View file

@ -1,17 +1,16 @@
//! Nvmcerature sensor interface.
use crate::pac;
use crate::peripherals::NVMC;
use crate::Unborrow;
use core::marker::PhantomData;
use core::ptr;
use core::slice;
use core::{ptr, slice};
use embassy_hal_common::unborrow;
use embedded_storage::nor_flash::{
ErrorType, MultiwriteNorFlash, NorFlash, NorFlashError, NorFlashErrorKind, ReadNorFlash,
};
use crate::peripherals::NVMC;
use crate::{pac, Unborrow};
pub const PAGE_SIZE: usize = 4096;
pub const FLASH_SIZE: usize = crate::chip::FLASH_SIZE;

View file

@ -1,11 +1,9 @@
use core::marker::PhantomData;
use crate::Unborrow;
use embassy_hal_common::unborrow;
use crate::pac;
use super::{Channel, ConfigurableChannel, Event, Ppi, Task};
use crate::{pac, Unborrow};
const DPPI_ENABLE_BIT: u32 = 0x8000_0000;
const DPPI_CHANNEL_MASK: u32 = 0x0000_00FF;
@ -21,12 +19,7 @@ impl<'d, C: ConfigurableChannel> Ppi<'d, C, 1, 1> {
}
impl<'d, C: ConfigurableChannel> Ppi<'d, C, 1, 2> {
pub fn new_one_to_two(
ch: impl Unborrow<Target = C> + 'd,
event: Event,
task1: Task,
task2: Task,
) -> Self {
pub fn new_one_to_two(ch: impl Unborrow<Target = C> + 'd, event: Event, task1: Task, task2: Task) -> Self {
Ppi::new_many_to_many(ch, [event], [task1, task2])
}
}
@ -64,9 +57,7 @@ impl<'d, C: ConfigurableChannel, const EVENT_COUNT: usize, const TASK_COUNT: usi
}
}
impl<'d, C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize>
Ppi<'d, C, EVENT_COUNT, TASK_COUNT>
{
impl<'d, C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize> Ppi<'d, C, EVENT_COUNT, TASK_COUNT> {
/// Enables the channel.
pub fn enable(&mut self) {
let n = self.ch.number();
@ -80,9 +71,7 @@ impl<'d, C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize>
}
}
impl<'d, C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize> Drop
for Ppi<'d, C, EVENT_COUNT, TASK_COUNT>
{
impl<'d, C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize> Drop for Ppi<'d, C, EVENT_COUNT, TASK_COUNT> {
fn drop(&mut self) {
self.disable();

View file

@ -15,12 +15,13 @@
//! many tasks and events, but any single task or event can only be coupled with one channel.
//!
use crate::peripherals;
use crate::Unborrow;
use core::marker::PhantomData;
use core::ptr::NonNull;
use embassy_hal_common::unsafe_impl_unborrow;
use crate::{peripherals, Unborrow};
#[cfg(feature = "_dppi")]
mod dppi;
#[cfg(feature = "_ppi")]

View file

@ -1,10 +1,9 @@
use core::marker::PhantomData;
use crate::Unborrow;
use embassy_hal_common::unborrow;
use super::{Channel, ConfigurableChannel, Event, Ppi, StaticChannel, Task};
use crate::pac;
use crate::{pac, Unborrow};
impl Task {
fn reg_val(&self) -> u32 {
@ -55,12 +54,7 @@ impl<'d, C: ConfigurableChannel> Ppi<'d, C, 1, 1> {
#[cfg(not(feature = "nrf51"))] // Not for nrf51 because of the fork task
impl<'d, C: ConfigurableChannel> Ppi<'d, C, 1, 2> {
pub fn new_one_to_two(
ch: impl Unborrow<Target = C> + 'd,
event: Event,
task1: Task,
task2: Task,
) -> Self {
pub fn new_one_to_two(ch: impl Unborrow<Target = C> + 'd, event: Event, task1: Task, task2: Task) -> Self {
unborrow!(ch);
let r = regs();
@ -76,9 +70,7 @@ impl<'d, C: ConfigurableChannel> Ppi<'d, C, 1, 2> {
}
}
impl<'d, C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize>
Ppi<'d, C, EVENT_COUNT, TASK_COUNT>
{
impl<'d, C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize> Ppi<'d, C, EVENT_COUNT, TASK_COUNT> {
/// Enables the channel.
pub fn enable(&mut self) {
let n = self.ch.number();
@ -92,9 +84,7 @@ impl<'d, C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize>
}
}
impl<'d, C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize> Drop
for Ppi<'d, C, EVENT_COUNT, TASK_COUNT>
{
impl<'d, C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize> Drop for Ppi<'d, C, EVENT_COUNT, TASK_COUNT> {
fn drop(&mut self) {
self.disable();

View file

@ -1,16 +1,16 @@
#![macro_use]
use crate::Unborrow;
use core::marker::PhantomData;
use core::sync::atomic::{compiler_fence, Ordering};
use embassy_hal_common::unborrow;
use crate::gpio::sealed::Pin as _;
use crate::gpio::{AnyPin, Pin as GpioPin, PselBits};
use crate::interrupt::Interrupt;
use crate::pac;
use crate::ppi::{Event, Task};
use crate::util::slice_in_ram_or;
use crate::{pac, Unborrow};
/// SimplePwm is the traditional pwm interface you're probably used to, allowing
/// to simply set a duty cycle across up to four channels.
@ -68,14 +68,7 @@ impl<'d, T: Instance> SequencePwm<'d, T> {
config: Config,
) -> Result<Self, Error> {
unborrow!(ch0, ch1);
Self::new_inner(
pwm,
Some(ch0.degrade()),
Some(ch1.degrade()),
None,
None,
config,
)
Self::new_inner(pwm, Some(ch0.degrade()), Some(ch1.degrade()), None, None, config)
}
/// Create a new 3-channel PWM
@ -171,10 +164,8 @@ impl<'d, T: Instance> SequencePwm<'d, T> {
CounterMode::UpAndDown => w.updown().up_and_down(),
CounterMode::Up => w.updown().up(),
});
r.prescaler
.write(|w| w.prescaler().bits(config.prescaler as u8));
r.countertop
.write(|w| unsafe { w.countertop().bits(config.max_duty) });
r.prescaler.write(|w| w.prescaler().bits(config.prescaler as u8));
r.countertop.write(|w| unsafe { w.countertop().bits(config.max_duty) });
Ok(Self {
phantom: PhantomData,
@ -391,9 +382,7 @@ impl<'d, 's, T: Instance> SingleSequencer<'d, 's, T> {
pub fn start(&self, times: SingleSequenceMode) -> Result<(), Error> {
let (start_seq, times) = match times {
SingleSequenceMode::Times(n) if n == 1 => (StartSequence::One, SequenceMode::Loop(1)),
SingleSequenceMode::Times(n) if n & 1 == 1 => {
(StartSequence::One, SequenceMode::Loop((n / 2) + 1))
}
SingleSequenceMode::Times(n) if n & 1 == 1 => (StartSequence::One, SequenceMode::Loop((n / 2) + 1)),
SingleSequenceMode::Times(n) => (StartSequence::Zero, SequenceMode::Loop(n / 2)),
SingleSequenceMode::Infinite => (StartSequence::Zero, SequenceMode::Infinite),
};
@ -424,11 +413,7 @@ pub struct Sequencer<'d, 's, T: Instance> {
impl<'d, 's, T: Instance> Sequencer<'d, 's, T> {
/// Create a new double sequence. In the absence of sequence 1, sequence 0
/// will be used twice in the one loop.
pub fn new(
pwm: &'s mut SequencePwm<'d, T>,
sequence0: Sequence<'s>,
sequence1: Option<Sequence<'s>>,
) -> Self {
pub fn new(pwm: &'s mut SequencePwm<'d, T>, sequence0: Sequence<'s>, sequence1: Option<Sequence<'s>>) -> Self {
Sequencer {
_pwm: pwm,
sequence0,
@ -457,42 +442,26 @@ impl<'d, 's, T: Instance> Sequencer<'d, 's, T> {
let r = T::regs();
r.seq0
.refresh
.write(|w| unsafe { w.bits(sequence0.config.refresh) });
r.seq0
.enddelay
.write(|w| unsafe { w.bits(sequence0.config.end_delay) });
r.seq0
.ptr
.write(|w| unsafe { w.bits(sequence0.words.as_ptr() as u32) });
r.seq0
.cnt
.write(|w| unsafe { w.bits(sequence0.words.len() as u32) });
r.seq0.refresh.write(|w| unsafe { w.bits(sequence0.config.refresh) });
r.seq0.enddelay.write(|w| unsafe { w.bits(sequence0.config.end_delay) });
r.seq0.ptr.write(|w| unsafe { w.bits(sequence0.words.as_ptr() as u32) });
r.seq0.cnt.write(|w| unsafe { w.bits(sequence0.words.len() as u32) });
r.seq1
.refresh
.write(|w| unsafe { w.bits(alt_sequence.config.refresh) });
r.seq1.refresh.write(|w| unsafe { w.bits(alt_sequence.config.refresh) });
r.seq1
.enddelay
.write(|w| unsafe { w.bits(alt_sequence.config.end_delay) });
r.seq1
.ptr
.write(|w| unsafe { w.bits(alt_sequence.words.as_ptr() as u32) });
r.seq1
.cnt
.write(|w| unsafe { w.bits(alt_sequence.words.len() as u32) });
r.seq1.cnt.write(|w| unsafe { w.bits(alt_sequence.words.len() as u32) });
r.enable.write(|w| w.enable().enabled());
// defensive before seqstart
compiler_fence(Ordering::SeqCst);
let seqstart_index = if start_seq == StartSequence::One {
1
} else {
0
};
let seqstart_index = if start_seq == StartSequence::One { 1 } else { 0 };
match times {
// just the one time, no loop count
@ -604,10 +573,7 @@ pub enum CounterMode {
impl<'d, T: Instance> SimplePwm<'d, T> {
/// Create a new 1-channel PWM
#[allow(unused_unsafe)]
pub fn new_1ch(
pwm: impl Unborrow<Target = T> + 'd,
ch0: impl Unborrow<Target = impl GpioPin> + 'd,
) -> Self {
pub fn new_1ch(pwm: impl Unborrow<Target = T> + 'd, ch0: impl Unborrow<Target = impl GpioPin> + 'd) -> Self {
unborrow!(ch0);
Self::new_inner(pwm, Some(ch0.degrade()), None, None, None)
}
@ -632,13 +598,7 @@ impl<'d, T: Instance> SimplePwm<'d, T> {
ch2: impl Unborrow<Target = impl GpioPin> + 'd,
) -> Self {
unborrow!(ch0, ch1, ch2);
Self::new_inner(
pwm,
Some(ch0.degrade()),
Some(ch1.degrade()),
Some(ch2.degrade()),
None,
)
Self::new_inner(pwm, Some(ch0.degrade()), Some(ch1.degrade()), Some(ch2.degrade()), None)
}
/// Create a new 4-channel PWM
@ -709,9 +669,7 @@ impl<'d, T: Instance> SimplePwm<'d, T> {
// Enable
r.enable.write(|w| w.enable().enabled());
r.seq0
.ptr
.write(|w| unsafe { w.bits((&pwm.duty).as_ptr() as u32) });
r.seq0.ptr.write(|w| unsafe { w.bits((&pwm.duty).as_ptr() as u32) });
r.seq0.cnt.write(|w| unsafe { w.bits(4) });
r.seq0.refresh.write(|w| unsafe { w.bits(0) });
@ -750,9 +708,7 @@ impl<'d, T: Instance> SimplePwm<'d, T> {
self.duty[channel] = duty & 0x7FFF;
// reload ptr in case self was moved
r.seq0
.ptr
.write(|w| unsafe { w.bits((&self.duty).as_ptr() as u32) });
r.seq0.ptr.write(|w| unsafe { w.bits((&self.duty).as_ptr() as u32) });
// defensive before seqstart
compiler_fence(Ordering::SeqCst);

View file

@ -1,19 +1,18 @@
//! Quadrature decoder interface
use crate::gpio::sealed::Pin as _;
use crate::gpio::{AnyPin, Pin as GpioPin};
use crate::interrupt;
use crate::pac;
use crate::peripherals::QDEC;
use crate::interrupt::InterruptExt;
use crate::Unborrow;
use core::marker::PhantomData;
use core::task::Poll;
use embassy::waitqueue::AtomicWaker;
use embassy_hal_common::unborrow;
use futures::future::poll_fn;
use crate::gpio::sealed::Pin as _;
use crate::gpio::{AnyPin, Pin as GpioPin};
use crate::interrupt::InterruptExt;
use crate::peripherals::QDEC;
use crate::{interrupt, pac, Unborrow};
/// Quadrature decoder
pub struct Qdec<'d> {
phantom: PhantomData<&'d QDEC>,
@ -63,14 +62,7 @@ impl<'d> Qdec<'d> {
config: Config,
) -> Self {
unborrow!(a, b, led);
Self::new_inner(
qdec,
irq,
a.degrade(),
b.degrade(),
Some(led.degrade()),
config,
)
Self::new_inner(qdec, irq, a.degrade(), b.degrade(), Some(led.degrade()), config)
}
fn new_inner(
@ -139,9 +131,7 @@ impl<'d> Qdec<'d> {
});
irq.enable();
Self {
phantom: PhantomData,
}
Self { phantom: PhantomData }
}
/// Perform an asynchronous read of the decoder.

View file

@ -1,22 +1,20 @@
#![macro_use]
use crate::interrupt::{Interrupt, InterruptExt};
use crate::Unborrow;
use core::marker::PhantomData;
use core::ptr;
use core::task::Poll;
use embassy_hal_common::drop::DropBomb;
use embassy_hal_common::unborrow;
use futures::future::poll_fn;
use crate::gpio::sealed::Pin as _;
use crate::gpio::{self, Pin as GpioPin};
use crate::pac;
pub use crate::pac::qspi::ifconfig0::ADDRMODE_A as AddressMode;
pub use crate::pac::qspi::ifconfig0::PPSIZE_A as WritePageSize;
pub use crate::pac::qspi::ifconfig0::READOC_A as ReadOpcode;
pub use crate::pac::qspi::ifconfig0::WRITEOC_A as WriteOpcode;
use crate::interrupt::{Interrupt, InterruptExt};
pub use crate::pac::qspi::ifconfig0::{
ADDRMODE_A as AddressMode, PPSIZE_A as WritePageSize, READOC_A as ReadOpcode, WRITEOC_A as WriteOpcode,
};
use crate::{pac, Unborrow};
// TODO
// - config:
@ -168,12 +166,7 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
}
}
pub async fn custom_instruction(
&mut self,
opcode: u8,
req: &[u8],
resp: &mut [u8],
) -> Result<(), Error> {
pub async fn custom_instruction(&mut self, opcode: u8, req: &[u8], resp: &mut [u8]) -> Result<(), Error> {
let bomb = DropBomb::new();
let len = core::cmp::max(req.len(), resp.len()) as u8;
@ -188,12 +181,7 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
Ok(())
}
pub fn blocking_custom_instruction(
&mut self,
opcode: u8,
req: &[u8],
resp: &mut [u8],
) -> Result<(), Error> {
pub fn blocking_custom_instruction(&mut self, opcode: u8, req: &[u8], resp: &mut [u8]) -> Result<(), Error> {
let len = core::cmp::max(req.len(), resp.len()) as u8;
self.custom_instruction_start(opcode, req, len)?;
@ -292,15 +280,9 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
let r = T::regs();
r.read
.src
.write(|w| unsafe { w.src().bits(address as u32) });
r.read
.dst
.write(|w| unsafe { w.dst().bits(data.as_ptr() as u32) });
r.read
.cnt
.write(|w| unsafe { w.cnt().bits(data.len() as u32) });
r.read.src.write(|w| unsafe { w.src().bits(address as u32) });
r.read.dst.write(|w| unsafe { w.dst().bits(data.as_ptr() as u32) });
r.read.cnt.write(|w| unsafe { w.cnt().bits(data.len() as u32) });
r.events_ready.reset();
r.intenset.write(|w| w.ready().set());
@ -322,15 +304,9 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
}
let r = T::regs();
r.write
.src
.write(|w| unsafe { w.src().bits(data.as_ptr() as u32) });
r.write
.dst
.write(|w| unsafe { w.dst().bits(address as u32) });
r.write
.cnt
.write(|w| unsafe { w.cnt().bits(data.len() as u32) });
r.write.src.write(|w| unsafe { w.src().bits(data.as_ptr() as u32) });
r.write.dst.write(|w| unsafe { w.dst().bits(address as u32) });
r.write.cnt.write(|w| unsafe { w.cnt().bits(data.len() as u32) });
r.events_ready.reset();
r.intenset.write(|w| w.ready().set());
@ -346,9 +322,7 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Qspi<'d, T, FLASH_SIZE> {
}
let r = T::regs();
r.erase
.ptr
.write(|w| unsafe { w.ptr().bits(address as u32) });
r.erase.ptr.write(|w| unsafe { w.ptr().bits(address as u32) });
r.erase.len.write(|w| w.len()._4kb());
r.events_ready.reset();
@ -458,9 +432,7 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> Drop for Qspi<'d, T, FLASH_SIZE>
}
}
use embedded_storage::nor_flash::{
ErrorType, NorFlash, NorFlashError, NorFlashErrorKind, ReadNorFlash,
};
use embedded_storage::nor_flash::{ErrorType, NorFlash, NorFlashError, NorFlashErrorKind, ReadNorFlash};
impl<'d, T: Instance, const FLASH_SIZE: usize> ErrorType for Qspi<'d, T, FLASH_SIZE> {
type Error = Error;

View file

@ -1,19 +1,16 @@
use core::marker::PhantomData;
use core::ptr;
use core::sync::atomic::AtomicPtr;
use core::sync::atomic::Ordering;
use core::sync::atomic::{AtomicPtr, Ordering};
use core::task::Poll;
use crate::interrupt::InterruptExt;
use crate::Unborrow;
use embassy::waitqueue::AtomicWaker;
use embassy_hal_common::drop::OnDrop;
use embassy_hal_common::unborrow;
use futures::future::poll_fn;
use crate::interrupt;
use crate::pac;
use crate::interrupt::InterruptExt;
use crate::peripherals::RNG;
use crate::{interrupt, pac, Unborrow};
impl RNG {
fn regs() -> &'static pac::rng::RegisterBlock {
@ -48,10 +45,7 @@ impl<'d> Rng<'d> {
/// e.g. using `mem::forget`.
///
/// The synchronous API is safe.
pub fn new(
_rng: impl Unborrow<Target = RNG> + 'd,
irq: impl Unborrow<Target = interrupt::RNG> + 'd,
) -> Self {
pub fn new(_rng: impl Unborrow<Target = RNG> + 'd, irq: impl Unborrow<Target = interrupt::RNG> + 'd) -> Self {
unborrow!(irq);
let this = Self {

View file

@ -1,29 +1,23 @@
#![macro_use]
use crate::interrupt::InterruptExt;
use crate::Unborrow;
use core::marker::PhantomData;
use core::sync::atomic::{compiler_fence, Ordering};
use core::task::Poll;
use embassy::waitqueue::AtomicWaker;
use embassy_hal_common::unborrow;
use futures::future::poll_fn;
use crate::interrupt;
use crate::ppi::{ConfigurableChannel, Event, Ppi, Task};
use crate::timer::{Frequency, Instance as TimerInstance, Timer};
use crate::{pac, peripherals};
use pac::{saadc, SAADC};
use saadc::ch::config::{GAIN_A, REFSEL_A, RESP_A, TACQ_A};
// We treat the positive and negative channels with the same enum values to keep our type tidy and given they are the same
pub(crate) use saadc::ch::pselp::PSELP_A as InputChannel;
use saadc::oversample::OVERSAMPLE_A;
use saadc::resolution::VAL_A;
use saadc::{
ch::config::{GAIN_A, REFSEL_A, RESP_A, TACQ_A},
oversample::OVERSAMPLE_A,
resolution::VAL_A,
};
use crate::interrupt::InterruptExt;
use crate::ppi::{ConfigurableChannel, Event, Ppi, Task};
use crate::timer::{Frequency, Instance as TimerInstance, Timer};
use crate::{interrupt, pac, peripherals, Unborrow};
#[derive(Debug, Clone, Copy, PartialEq, Eq)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
@ -178,23 +172,17 @@ impl<'d, const N: usize> Saadc<'d, N> {
let r = unsafe { &*SAADC::ptr() };
let Config {
resolution,
oversample,
} = config;
let Config { resolution, oversample } = config;
// Configure channels
r.enable.write(|w| w.enable().enabled());
r.resolution.write(|w| w.val().variant(resolution.into()));
r.oversample
.write(|w| w.oversample().variant(oversample.into()));
r.oversample.write(|w| w.oversample().variant(oversample.into()));
for (i, cc) in channel_configs.iter().enumerate() {
r.ch[i].pselp.write(|w| w.pselp().variant(cc.p_channel));
if let Some(n_channel) = cc.n_channel {
r.ch[i]
.pseln
.write(|w| unsafe { w.pseln().bits(n_channel as u8) });
r.ch[i].pseln.write(|w| unsafe { w.pseln().bits(n_channel as u8) });
}
r.ch[i].config.write(|w| {
w.refsel().variant(cc.reference.into());
@ -223,9 +211,7 @@ impl<'d, const N: usize> Saadc<'d, N> {
irq.unpend();
irq.enable();
Self {
phantom: PhantomData,
}
Self { phantom: PhantomData }
}
fn on_interrupt(_ctx: *mut ()) {
@ -285,12 +271,8 @@ impl<'d, const N: usize> Saadc<'d, N> {
let r = Self::regs();
// Set up the DMA
r.result
.ptr
.write(|w| unsafe { w.ptr().bits(buf.as_mut_ptr() as u32) });
r.result
.maxcnt
.write(|w| unsafe { w.maxcnt().bits(N as _) });
r.result.ptr.write(|w| unsafe { w.ptr().bits(buf.as_mut_ptr() as u32) });
r.result.maxcnt.write(|w| unsafe { w.maxcnt().bits(N as _) });
// Reset and enable the end event
r.events_end.reset();
@ -353,11 +335,8 @@ impl<'d, const N: usize> Saadc<'d, N> {
// We want the task start to effectively short with the last one ending so
// we don't miss any samples. It'd be great for the SAADC to offer a SHORTS
// register instead, but it doesn't, so we must use PPI.
let mut start_ppi = Ppi::new_one_to_one(
ppi_ch1,
Event::from_reg(&r.events_end),
Task::from_reg(&r.tasks_start),
);
let mut start_ppi =
Ppi::new_one_to_one(ppi_ch1, Event::from_reg(&r.events_end), Task::from_reg(&r.tasks_start));
start_ppi.enable();
let mut timer = Timer::new(timer);
@ -365,11 +344,7 @@ impl<'d, const N: usize> Saadc<'d, N> {
timer.cc(0).write(sample_counter);
timer.cc(0).short_compare_clear();
let mut sample_ppi = Ppi::new_one_to_one(
ppi_ch2,
timer.cc(0).event_compare(),
Task::from_reg(&r.tasks_sample),
);
let mut sample_ppi = Ppi::new_one_to_one(ppi_ch2, timer.cc(0).event_compare(), Task::from_reg(&r.tasks_sample));
timer.start();
@ -417,9 +392,7 @@ impl<'d, const N: usize> Saadc<'d, N> {
r.result
.ptr
.write(|w| unsafe { w.ptr().bits(bufs[0].as_mut_ptr() as u32) });
r.result
.maxcnt
.write(|w| unsafe { w.maxcnt().bits((N0 * N) as _) });
r.result.maxcnt.write(|w| unsafe { w.maxcnt().bits((N0 * N) as _) });
// Reset and enable the events
r.events_end.reset();
@ -500,8 +473,7 @@ impl<'d> Saadc<'d, 1> {
) where
S: FnMut(&[[i16; 1]]) -> SamplerState,
{
self.run_sampler(bufs, Some(sample_rate_divisor), || {}, sampler)
.await;
self.run_sampler(bufs, Some(sample_rate_divisor), || {}, sampler).await;
}
}

View file

@ -1,23 +1,20 @@
#![macro_use]
use crate::interrupt::InterruptExt;
use crate::Unborrow;
use core::marker::PhantomData;
use core::sync::atomic::{compiler_fence, Ordering};
use core::task::Poll;
use embassy_hal_common::unborrow;
pub use embedded_hal_02::spi::{Mode, Phase, Polarity, MODE_0, MODE_1, MODE_2, MODE_3};
use futures::future::poll_fn;
pub use pac::spim0::frequency::FREQUENCY_A as Frequency;
use crate::chip::FORCE_COPY_BUFFER_SIZE;
use crate::gpio::sealed::Pin as _;
use crate::gpio::{self, AnyPin};
use crate::gpio::{Pin as GpioPin, PselBits};
use crate::interrupt::Interrupt;
use crate::util::{slice_ptr_parts, slice_ptr_parts_mut};
use crate::{pac, util::slice_in_ram_or};
pub use embedded_hal_02::spi::{Mode, Phase, Polarity, MODE_0, MODE_1, MODE_2, MODE_3};
pub use pac::spim0::frequency::FREQUENCY_A as Frequency;
use crate::gpio::{self, AnyPin, Pin as GpioPin, PselBits};
use crate::interrupt::{Interrupt, InterruptExt};
use crate::util::{slice_in_ram_or, slice_ptr_parts, slice_ptr_parts_mut};
use crate::{pac, Unborrow};
#[derive(Debug, Clone, Copy, PartialEq, Eq)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
@ -183,9 +180,7 @@ impl<'d, T: Instance> Spim<'d, T> {
irq.unpend();
irq.enable();
Self {
phantom: PhantomData,
}
Self { phantom: PhantomData }
}
fn on_interrupt(_: *mut ()) {
@ -295,11 +290,7 @@ impl<'d, T: Instance> Spim<'d, T> {
}
/// Same as [`blocking_transfer`](Spim::blocking_transfer) but will fail instead of copying data into RAM. Consult the module level documentation to learn more.
pub fn blocking_transfer_from_ram(
&mut self,
read: &mut [u8],
write: &[u8],
) -> Result<(), Error> {
pub fn blocking_transfer_from_ram(&mut self, read: &mut [u8], write: &[u8]) -> Result<(), Error> {
self.blocking_inner(read, write)
}

View file

@ -1,18 +1,18 @@
//! Temperature sensor interface.
use crate::interrupt;
use crate::pac;
use crate::peripherals::TEMP;
use crate::interrupt::InterruptExt;
use crate::Unborrow;
use core::marker::PhantomData;
use core::task::Poll;
use embassy::waitqueue::AtomicWaker;
use embassy_hal_common::{drop::OnDrop, unborrow};
use embassy_hal_common::drop::OnDrop;
use embassy_hal_common::unborrow;
use fixed::types::I30F2;
use futures::future::poll_fn;
use crate::interrupt::InterruptExt;
use crate::peripherals::TEMP;
use crate::{interrupt, pac, Unborrow};
/// Integrated temperature sensor.
pub struct Temp<'d> {
_temp: PhantomData<&'d TEMP>,
@ -22,10 +22,7 @@ pub struct Temp<'d> {
static WAKER: AtomicWaker = AtomicWaker::new();
impl<'d> Temp<'d> {
pub fn new(
_t: impl Unborrow<Target = TEMP> + 'd,
irq: impl Unborrow<Target = interrupt::TEMP> + 'd,
) -> Self {
pub fn new(_t: impl Unborrow<Target = TEMP> + 'd, irq: impl Unborrow<Target = interrupt::TEMP> + 'd) -> Self {
unborrow!(_t, irq);
// Enable interrupt that signals temperature values

View file

@ -1,14 +1,14 @@
use crate::interrupt::{Interrupt, InterruptExt};
use core::cell::Cell;
use core::sync::atomic::{compiler_fence, AtomicU32, AtomicU8, Ordering};
use core::{mem, ptr};
use critical_section::CriticalSection;
use embassy::blocking_mutex::raw::CriticalSectionRawMutex;
use embassy::blocking_mutex::CriticalSectionMutex as Mutex;
use embassy::time::driver::{AlarmHandle, Driver};
use crate::interrupt;
use crate::pac;
use crate::interrupt::{Interrupt, InterruptExt};
use crate::{interrupt, pac};
fn rtc() -> &'static pac::rtc0::RegisterBlock {
unsafe { &*pac::RTC1::ptr() }
@ -220,15 +220,13 @@ impl Driver for RtcDriver {
}
unsafe fn allocate_alarm(&self) -> Option<AlarmHandle> {
let id = self
.alarm_count
.fetch_update(Ordering::AcqRel, Ordering::Acquire, |x| {
if x < ALARM_COUNT as u8 {
Some(x + 1)
} else {
None
}
});
let id = self.alarm_count.fetch_update(Ordering::AcqRel, Ordering::Acquire, |x| {
if x < ALARM_COUNT as u8 {
Some(x + 1)
} else {
None
}
});
match id {
Ok(id) => Some(AlarmHandle::new(id)),

View file

@ -3,16 +3,14 @@
use core::marker::PhantomData;
use core::task::Poll;
use crate::interrupt::Interrupt;
use crate::interrupt::InterruptExt;
use crate::Unborrow;
use embassy::waitqueue::AtomicWaker;
use embassy_hal_common::drop::OnDrop;
use embassy_hal_common::unborrow;
use futures::future::poll_fn;
use crate::pac;
use crate::interrupt::{Interrupt, InterruptExt};
use crate::ppi::{Event, Task};
use crate::{pac, Unborrow};
pub(crate) mod sealed {
@ -131,9 +129,7 @@ impl<'d, T: Instance, I: TimerType> Timer<'d, T, I> {
fn new_irqless(_timer: impl Unborrow<Target = T> + 'd) -> Self {
let regs = T::regs();
let mut this = Self {
phantom: PhantomData,
};
let mut this = Self { phantom: PhantomData };
// Stop the timer before doing anything else,
// since changing BITMODE while running can cause 'unpredictable behaviour' according to the specification.
@ -233,11 +229,7 @@ impl<'d, T: Instance, I: TimerType> Timer<'d, T, I> {
/// Panics if `n` >= the number of CC registers this timer has (4 for a normal timer, 6 for an extended timer).
pub fn cc(&mut self, n: usize) -> Cc<T, I> {
if n >= T::CCS {
panic!(
"Cannot get CC register {} of timer with {} CC registers.",
n,
T::CCS
);
panic!("Cannot get CC register {} of timer with {} CC registers.", n, T::CCS);
}
Cc {
n,

View file

@ -6,12 +6,12 @@
//!
//! - nRF52832: Section 33
//! - nRF52840: Section 6.31
use crate::interrupt::{Interrupt, InterruptExt};
use crate::Unborrow;
use core::future::Future;
use core::marker::PhantomData;
use core::sync::atomic::{compiler_fence, Ordering::SeqCst};
use core::sync::atomic::compiler_fence;
use core::sync::atomic::Ordering::SeqCst;
use core::task::Poll;
#[cfg(feature = "time")]
use embassy::time::{Duration, Instant};
use embassy::waitqueue::AtomicWaker;
@ -19,10 +19,10 @@ use embassy_hal_common::unborrow;
use futures::future::poll_fn;
use crate::chip::{EASY_DMA_SIZE, FORCE_COPY_BUFFER_SIZE};
use crate::gpio;
use crate::gpio::Pin as GpioPin;
use crate::pac;
use crate::interrupt::{Interrupt, InterruptExt};
use crate::util::{slice_in_ram, slice_in_ram_or};
use crate::{gpio, pac, Unborrow};
pub enum Frequency {
#[doc = "26738688: 100 kbps"]
@ -134,9 +134,7 @@ impl<'d, T: Instance> Twim<'d, T> {
irq.unpend();
irq.enable();
Self {
phantom: PhantomData,
}
Self { phantom: PhantomData }
}
fn on_interrupt(_: *mut ()) {
@ -319,12 +317,7 @@ impl<'d, T: Instance> Twim<'d, T> {
})
}
fn setup_write_from_ram(
&mut self,
address: u8,
buffer: &[u8],
inten: bool,
) -> Result<(), Error> {
fn setup_write_from_ram(&mut self, address: u8, buffer: &[u8], inten: bool) -> Result<(), Error> {
let r = T::regs();
compiler_fence(SeqCst);
@ -506,12 +499,7 @@ impl<'d, T: Instance> Twim<'d, T> {
///
/// The buffers must have a length of at most 255 bytes on the nRF52832
/// and at most 65535 bytes on the nRF52840.
pub fn blocking_write_read(
&mut self,
address: u8,
wr_buffer: &[u8],
rd_buffer: &mut [u8],
) -> Result<(), Error> {
pub fn blocking_write_read(&mut self, address: u8, wr_buffer: &[u8], rd_buffer: &mut [u8]) -> Result<(), Error> {
self.setup_write_read(address, wr_buffer, rd_buffer, false)?;
self.blocking_wait();
compiler_fence(SeqCst);
@ -543,12 +531,7 @@ impl<'d, T: Instance> Twim<'d, T> {
///
/// See [`blocking_write`].
#[cfg(feature = "time")]
pub fn blocking_write_timeout(
&mut self,
address: u8,
buffer: &[u8],
timeout: Duration,
) -> Result<(), Error> {
pub fn blocking_write_timeout(&mut self, address: u8, buffer: &[u8], timeout: Duration) -> Result<(), Error> {
self.setup_write(address, buffer, false)?;
self.blocking_wait_timeout(timeout)?;
compiler_fence(SeqCst);
@ -578,12 +561,7 @@ impl<'d, T: Instance> Twim<'d, T> {
/// The buffer must have a length of at most 255 bytes on the nRF52832
/// and at most 65535 bytes on the nRF52840.
#[cfg(feature = "time")]
pub fn blocking_read_timeout(
&mut self,
address: u8,
buffer: &mut [u8],
timeout: Duration,
) -> Result<(), Error> {
pub fn blocking_read_timeout(&mut self, address: u8, buffer: &mut [u8], timeout: Duration) -> Result<(), Error> {
self.setup_read(address, buffer, false)?;
self.blocking_wait_timeout(timeout)?;
compiler_fence(SeqCst);
@ -662,12 +640,7 @@ impl<'d, T: Instance> Twim<'d, T> {
Ok(())
}
pub async fn write_read(
&mut self,
address: u8,
wr_buffer: &[u8],
rd_buffer: &mut [u8],
) -> Result<(), Error> {
pub async fn write_read(&mut self, address: u8, wr_buffer: &[u8], rd_buffer: &mut [u8]) -> Result<(), Error> {
self.setup_write_read(address, wr_buffer, rd_buffer, true)?;
self.async_wait().await;
compiler_fence(SeqCst);
@ -786,12 +759,7 @@ mod eh02 {
impl<'a, T: Instance> embedded_hal_02::blocking::i2c::WriteRead for Twim<'a, T> {
type Error = Error;
fn write_read<'w>(
&mut self,
addr: u8,
bytes: &'w [u8],
buffer: &'w mut [u8],
) -> Result<(), Error> {
fn write_read<'w>(&mut self, addr: u8, bytes: &'w [u8], buffer: &'w mut [u8]) -> Result<(), Error> {
self.blocking_write_read(addr, bytes, buffer)
}
}
@ -809,12 +777,12 @@ mod eh1 {
Self::Transmit => embedded_hal_1::i2c::ErrorKind::Other,
Self::Receive => embedded_hal_1::i2c::ErrorKind::Other,
Self::DMABufferNotInDataMemory => embedded_hal_1::i2c::ErrorKind::Other,
Self::AddressNack => embedded_hal_1::i2c::ErrorKind::NoAcknowledge(
embedded_hal_1::i2c::NoAcknowledgeSource::Address,
),
Self::DataNack => embedded_hal_1::i2c::ErrorKind::NoAcknowledge(
embedded_hal_1::i2c::NoAcknowledgeSource::Data,
),
Self::AddressNack => {
embedded_hal_1::i2c::ErrorKind::NoAcknowledge(embedded_hal_1::i2c::NoAcknowledgeSource::Address)
}
Self::DataNack => {
embedded_hal_1::i2c::ErrorKind::NoAcknowledge(embedded_hal_1::i2c::NoAcknowledgeSource::Data)
}
Self::Overrun => embedded_hal_1::i2c::ErrorKind::Overrun,
Self::Timeout => embedded_hal_1::i2c::ErrorKind::Other,
}
@ -841,24 +809,14 @@ mod eh1 {
todo!();
}
fn write_iter_read<B>(
&mut self,
_address: u8,
_bytes: B,
_buffer: &mut [u8],
) -> Result<(), Self::Error>
fn write_iter_read<B>(&mut self, _address: u8, _bytes: B, _buffer: &mut [u8]) -> Result<(), Self::Error>
where
B: IntoIterator<Item = u8>,
{
todo!();
}
fn write_read(
&mut self,
address: u8,
wr_buffer: &[u8],
rd_buffer: &mut [u8],
) -> Result<(), Self::Error> {
fn write_read(&mut self, address: u8, wr_buffer: &[u8], rd_buffer: &mut [u8]) -> Result<(), Self::Error> {
self.blocking_write_read(address, wr_buffer, rd_buffer)
}
@ -870,11 +828,7 @@ mod eh1 {
todo!();
}
fn transaction_iter<'a, O>(
&mut self,
_address: u8,
_operations: O,
) -> Result<(), Self::Error>
fn transaction_iter<'a, O>(&mut self, _address: u8, _operations: O) -> Result<(), Self::Error>
where
O: IntoIterator<Item = embedded_hal_1::i2c::blocking::Operation<'a>>,
{

View file

@ -13,27 +13,24 @@
//! memory may be used given that buffers are passed in directly to its read and write
//! methods.
use crate::interrupt::InterruptExt;
use crate::Unborrow;
use core::marker::PhantomData;
use core::sync::atomic::{compiler_fence, Ordering};
use core::task::Poll;
use embassy_hal_common::drop::OnDrop;
use embassy_hal_common::unborrow;
use futures::future::poll_fn;
// Re-export SVD variants to allow user to directly set values.
pub use pac::uarte0::{baudrate::BAUDRATE_A as Baudrate, config::PARITY_A as Parity};
use crate::chip::{EASY_DMA_SIZE, FORCE_COPY_BUFFER_SIZE};
use crate::gpio::sealed::Pin as _;
use crate::gpio::{self, AnyPin, Pin as GpioPin, PselBits};
use crate::interrupt::Interrupt;
use crate::pac;
use crate::interrupt::{Interrupt, InterruptExt};
use crate::ppi::{AnyConfigurableChannel, ConfigurableChannel, Event, Ppi, Task};
use crate::timer::Instance as TimerInstance;
use crate::timer::{Frequency, Timer};
use crate::timer::{Frequency, Instance as TimerInstance, Timer};
use crate::util::slice_in_ram_or;
// Re-export SVD variants to allow user to directly set values.
pub use pac::uarte0::{baudrate::BAUDRATE_A as Baudrate, config::PARITY_A as Parity};
use crate::{pac, Unborrow};
#[non_exhaustive]
pub struct Config {
@ -182,12 +179,8 @@ impl<'d, T: Instance> Uarte<'d, T> {
Self {
phantom: PhantomData,
tx: UarteTx {
phantom: PhantomData,
},
rx: UarteRx {
phantom: PhantomData,
},
tx: UarteTx { phantom: PhantomData },
rx: UarteRx { phantom: PhantomData },
}
}
@ -893,9 +886,7 @@ mod eh02 {
}
}
impl<'d, U: Instance, T: TimerInstance> embedded_hal_02::blocking::serial::Write<u8>
for UarteWithIdle<'d, U, T>
{
impl<'d, U: Instance, T: TimerInstance> embedded_hal_02::blocking::serial::Write<u8> for UarteWithIdle<'d, U, T> {
type Error = Error;
fn bwrite_all(&mut self, buffer: &[u8]) -> Result<(), Self::Error> {
@ -956,9 +947,7 @@ mod eh1 {
type Error = Error;
}
impl<'d, U: Instance, T: TimerInstance> embedded_hal_1::serial::ErrorType
for UarteWithIdle<'d, U, T>
{
impl<'d, U: Instance, T: TimerInstance> embedded_hal_1::serial::ErrorType for UarteWithIdle<'d, U, T> {
type Error = Error;
}
}

View file

@ -1,25 +1,23 @@
#![macro_use]
use crate::interrupt::InterruptExt;
use crate::Unborrow;
use core::marker::PhantomData;
use core::mem::MaybeUninit;
use core::sync::atomic::{compiler_fence, AtomicU32, Ordering};
use core::task::Poll;
use cortex_m::peripheral::NVIC;
use embassy::waitqueue::AtomicWaker;
use embassy_hal_common::unborrow;
pub use embassy_usb;
use embassy_usb::driver::{self, EndpointError, Event, Unsupported};
use embassy_usb::types::{EndpointAddress, EndpointInfo, EndpointType, UsbDirection};
use futures::future::poll_fn;
use futures::Future;
pub use embassy_usb;
use pac::usbd::RegisterBlock;
use crate::interrupt::Interrupt;
use crate::pac;
use crate::interrupt::{Interrupt, InterruptExt};
use crate::util::slice_in_ram;
use crate::{pac, Unborrow};
const NEW_AW: AtomicWaker = AtomicWaker::new();
static BUS_WAKER: AtomicWaker = NEW_AW;
@ -35,10 +33,7 @@ pub struct Driver<'d, T: Instance> {
}
impl<'d, T: Instance> Driver<'d, T> {
pub fn new(
_usb: impl Unborrow<Target = T> + 'd,
irq: impl Unborrow<Target = T::Interrupt> + 'd,
) -> Self {
pub fn new(_usb: impl Unborrow<Target = T> + 'd, irq: impl Unborrow<Target = T::Interrupt> + 'd) -> Self {
unborrow!(irq);
irq.set_handler(Self::on_interrupt);
irq.unpend();
@ -143,9 +138,7 @@ impl<'d, T: Instance> driver::Driver<'d> for Driver<'d, T> {
fn start(self, control_max_packet_size: u16) -> (Self::Bus, Self::ControlPipe) {
(
Bus {
phantom: PhantomData,
},
Bus { phantom: PhantomData },
ControlPipe {
_phantom: PhantomData,
max_packet_size: control_max_packet_size,
@ -266,8 +259,7 @@ impl<'d, T: Instance> driver::Bus for Bus<'d, T> {
let regs = T::regs();
unsafe {
if ep_addr.index() == 0 {
regs.tasks_ep0stall
.write(|w| w.tasks_ep0stall().bit(stalled));
regs.tasks_ep0stall.write(|w| w.tasks_ep0stall().bit(stalled));
} else {
regs.epstall.write(|w| {
w.ep().bits(ep_addr.index() as u8 & 0b111);
@ -370,8 +362,7 @@ impl<'d, T: Instance> driver::Bus for Bus<'d, T> {
regs.eventcause.write(|w| w.usbwuallowed().set_bit());
regs.dpdmvalue.write(|w| w.state().resume());
regs.tasks_dpdmdrive
.write(|w| w.tasks_dpdmdrive().set_bit());
regs.tasks_dpdmdrive.write(|w| w.tasks_dpdmdrive().set_bit());
Poll::Ready(())
} else {
@ -520,11 +511,7 @@ unsafe fn read_dma<T: Instance>(i: usize, buf: &mut [u8]) -> Result<usize, Endpo
dma_start();
regs.events_endepout[i].reset();
regs.tasks_startepout[i].write(|w| w.tasks_startepout().set_bit());
while regs.events_endepout[i]
.read()
.events_endepout()
.bit_is_clear()
{}
while regs.events_endepout[i].read().events_endepout().bit_is_clear() {}
regs.events_endepout[i].reset();
dma_end();
@ -579,9 +566,7 @@ impl<'d, T: Instance> driver::EndpointOut for Endpoint<'d, T, Out> {
let i = self.info.addr.index();
assert!(i != 0);
self.wait_data_ready()
.await
.map_err(|_| EndpointError::Disabled)?;
self.wait_data_ready().await.map_err(|_| EndpointError::Disabled)?;
unsafe { read_dma::<T>(i, buf) }
}
@ -596,9 +581,7 @@ impl<'d, T: Instance> driver::EndpointIn for Endpoint<'d, T, In> {
let i = self.info.addr.index();
assert!(i != 0);
self.wait_data_ready()
.await
.map_err(|_| EndpointError::Disabled)?;
self.wait_data_ready().await.map_err(|_| EndpointError::Disabled)?;
unsafe { write_dma::<T>(i, buf) }
@ -659,20 +642,14 @@ impl<'d, T: Instance> driver::ControlPipe for ControlPipe<'d, T> {
}
}
fn data_out<'a>(
&'a mut self,
buf: &'a mut [u8],
_first: bool,
_last: bool,
) -> Self::DataOutFuture<'a> {
fn data_out<'a>(&'a mut self, buf: &'a mut [u8], _first: bool, _last: bool) -> Self::DataOutFuture<'a> {
async move {
let regs = T::regs();
regs.events_ep0datadone.reset();
// This starts a RX on EP0. events_ep0datadone notifies when done.
regs.tasks_ep0rcvout
.write(|w| w.tasks_ep0rcvout().set_bit());
regs.tasks_ep0rcvout.write(|w| w.tasks_ep0rcvout().set_bit());
// Wait until ready
regs.intenset.write(|w| {
@ -701,12 +678,7 @@ impl<'d, T: Instance> driver::ControlPipe for ControlPipe<'d, T> {
}
}
fn data_in<'a>(
&'a mut self,
buf: &'a [u8],
_first: bool,
last: bool,
) -> Self::DataInFuture<'a> {
fn data_in<'a>(&'a mut self, buf: &'a [u8], _first: bool, last: bool) -> Self::DataInFuture<'a> {
async move {
let regs = T::regs();
regs.events_ep0datadone.reset();
@ -745,8 +717,7 @@ impl<'d, T: Instance> driver::ControlPipe for ControlPipe<'d, T> {
fn accept<'a>(&'a mut self) -> Self::AcceptFuture<'a> {
async move {
let regs = T::regs();
regs.tasks_ep0status
.write(|w| w.tasks_ep0status().bit(true));
regs.tasks_ep0status.write(|w| w.tasks_ep0status().bit(true));
}
}

View file

@ -47,11 +47,9 @@ pub unsafe fn init() {
start_xosc();
// Before we touch PLLs, switch sys and ref cleanly away from their aux sources.
c.clk_sys_ctrl()
.modify(|w| w.set_src(ClkSysCtrlSrc::CLK_REF));
c.clk_sys_ctrl().modify(|w| w.set_src(ClkSysCtrlSrc::CLK_REF));
while c.clk_sys_selected().read() != 1 {}
c.clk_ref_ctrl()
.modify(|w| w.set_src(ClkRefCtrlSrc::ROSC_CLKSRC_PH));
c.clk_ref_ctrl().modify(|w| w.set_src(ClkRefCtrlSrc::ROSC_CLKSRC_PH));
while c.clk_ref_selected().read() != 1 {}
// Configure PLLs
@ -135,9 +133,7 @@ unsafe fn start_xosc() {
.write(|w| w.set_freq_range(pac::xosc::vals::CtrlFreqRange::_1_15MHZ));
let startup_delay = (((XOSC_MHZ * 1_000_000) / 1000) + 128) / 256;
pac::XOSC
.startup()
.write(|w| w.set_delay(startup_delay as u16));
pac::XOSC.startup().write(|w| w.set_delay(startup_delay as u16));
pac::XOSC.ctrl().write(|w| {
w.set_freq_range(pac::xosc::vals::CtrlFreqRange::_1_15MHZ);
w.set_enable(pac::xosc::vals::Enable::ENABLE);
@ -145,13 +141,7 @@ unsafe fn start_xosc() {
while !pac::XOSC.status().read().stable() {}
}
unsafe fn configure_pll(
p: pac::pll::Pll,
refdiv: u32,
vco_freq: u32,
post_div1: u8,
post_div2: u8,
) {
unsafe fn configure_pll(p: pac::pll::Pll, refdiv: u32, vco_freq: u32, post_div1: u8, post_div2: u8) {
let ref_freq = XOSC_MHZ * 1_000_000 / refdiv;
let fbdiv = vco_freq / ref_freq;

View file

@ -1,13 +1,11 @@
use core::convert::Infallible;
use core::marker::PhantomData;
use crate::pac;
use embassy_hal_common::{unborrow, unsafe_impl_unborrow};
use crate::pac::common::{Reg, RW};
use crate::pac::SIO;
use crate::peripherals;
use crate::Unborrow;
use embassy_hal_common::{unborrow, unsafe_impl_unborrow};
use crate::{pac, peripherals, Unborrow};
/// Represents a digital input or output level.
#[derive(Debug, Eq, PartialEq)]
@ -195,10 +193,7 @@ impl<'d, T: Pin> OutputOpenDrain<'d, T> {
pub fn set_high(&mut self) {
// For Open Drain High, disable the output pin.
unsafe {
self.pin
.sio_oe()
.value_clr()
.write_value(1 << self.pin.pin());
self.pin.sio_oe().value_clr().write_value(1 << self.pin.pin());
}
}
@ -207,10 +202,7 @@ impl<'d, T: Pin> OutputOpenDrain<'d, T> {
pub fn set_low(&mut self) {
// For Open Drain Low, enable the output pin.
unsafe {
self.pin
.sio_oe()
.value_set()
.write_value(1 << self.pin.pin());
self.pin.sio_oe().value_set().write_value(1 << self.pin.pin());
}
}

View file

@ -5,9 +5,9 @@
// Re-exports
pub use embassy_cortex_m::interrupt::*;
use embassy_macros::cortex_m_interrupt_declare as declare;
use crate::pac::Interrupt as InterruptEnum;
use embassy_macros::cortex_m_interrupt_declare as declare;
declare!(TIMER_IRQ_0);
declare!(TIMER_IRQ_1);
declare!(TIMER_IRQ_2);

View file

@ -17,15 +17,14 @@ mod reset;
// Reexports
pub use embassy_cortex_m::executor;
pub use embassy_hal_common::{unborrow, Unborrow};
pub use embassy_macros::cortex_m_interrupt as interrupt;
#[cfg(feature = "unstable-pac")]
pub use rp2040_pac2 as pac;
#[cfg(not(feature = "unstable-pac"))]
pub(crate) use rp2040_pac2 as pac;
pub use embassy_cortex_m::executor;
pub use embassy_hal_common::{unborrow, Unborrow};
pub use embassy_macros::cortex_m_interrupt as interrupt;
embassy_hal_common::peripherals! {
PIN_0,
PIN_1,

View file

@ -1,7 +1,7 @@
use crate::pac;
pub use pac::resets::regs::Peripherals;
use crate::pac;
pub const ALL_PERIPHERALS: Peripherals = Peripherals(0x01ffffff);
pub unsafe fn reset(peris: Peripherals) {
@ -10,8 +10,6 @@ pub unsafe fn reset(peris: Peripherals) {
pub unsafe fn unreset_wait(peris: Peripherals) {
// TODO use the "atomic clear" register version
pac::RESETS
.reset()
.modify(|v| *v = Peripherals(v.0 & !peris.0));
pac::RESETS.reset().modify(|v| *v = Peripherals(v.0 & !peris.0));
while ((!pac::RESETS.reset_done().read().0) & peris.0) != 0 {}
}

View file

@ -1,13 +1,11 @@
use core::marker::PhantomData;
use crate::Unborrow;
use embassy_hal_common::unborrow;
pub use embedded_hal_02::spi::{Phase, Polarity};
use crate::gpio::sealed::Pin as _;
use crate::gpio::{AnyPin, Pin as GpioPin};
use crate::{pac, peripherals};
pub use embedded_hal_02::spi::{Phase, Polarity};
use crate::{pac, peripherals, Unborrow};
#[derive(Debug, Clone, Copy, PartialEq, Eq)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
@ -56,11 +54,7 @@ fn calc_prescs(freq: u32) -> (u8, u8) {
}
let presc = div_roundup(ratio, 256);
let postdiv = if presc == 1 {
ratio
} else {
div_roundup(ratio, presc)
};
let postdiv = if presc == 1 { ratio } else { div_roundup(ratio, presc) };
((presc * 2) as u8, (postdiv - 1) as u8)
}
@ -91,14 +85,7 @@ impl<'d, T: Instance> Spi<'d, T> {
config: Config,
) -> Self {
unborrow!(clk, mosi);
Self::new_inner(
inner,
Some(clk.degrade()),
Some(mosi.degrade()),
None,
None,
config,
)
Self::new_inner(inner, Some(clk.degrade()), Some(mosi.degrade()), None, None, config)
}
pub fn new_rxonly(
@ -108,14 +95,7 @@ impl<'d, T: Instance> Spi<'d, T> {
config: Config,
) -> Self {
unborrow!(clk, miso);
Self::new_inner(
inner,
Some(clk.degrade()),
None,
Some(miso.degrade()),
None,
config,
)
Self::new_inner(inner, Some(clk.degrade()), None, Some(miso.degrade()), None, config)
}
fn new_inner(

View file

@ -1,11 +1,12 @@
use crate::interrupt::{Interrupt, InterruptExt};
use atomic_polyfill::{AtomicU8, Ordering};
use core::cell::Cell;
use atomic_polyfill::{AtomicU8, Ordering};
use critical_section::CriticalSection;
use embassy::blocking_mutex::raw::CriticalSectionRawMutex;
use embassy::blocking_mutex::Mutex;
use embassy::time::driver::{AlarmHandle, Driver};
use crate::interrupt::{Interrupt, InterruptExt};
use crate::{interrupt, pac};
struct AlarmState {
@ -45,15 +46,13 @@ impl Driver for TimerDriver {
}
unsafe fn allocate_alarm(&self) -> Option<AlarmHandle> {
let id = self
.next_alarm
.fetch_update(Ordering::AcqRel, Ordering::Acquire, |x| {
if x < ALARM_COUNT as u8 {
Some(x + 1)
} else {
None
}
});
let id = self.next_alarm.fetch_update(Ordering::AcqRel, Ordering::Acquire, |x| {
if x < ALARM_COUNT as u8 {
Some(x + 1)
} else {
None
}
});
match id {
Ok(id) => Some(AlarmHandle::new(id)),

View file

@ -1,10 +1,9 @@
use core::marker::PhantomData;
use crate::Unborrow;
use embassy_hal_common::unborrow;
use gpio::Pin;
use crate::{gpio, pac, peripherals};
use crate::{gpio, pac, peripherals, Unborrow};
#[non_exhaustive]
pub struct Config {
@ -57,10 +56,8 @@ impl<'d, T: Instance> Uart<'d, T> {
}
// Load PL011's baud divisor registers
p.uartibrd()
.write_value(pac::uart::regs::Uartibrd(baud_ibrd));
p.uartfbrd()
.write_value(pac::uart::regs::Uartfbrd(baud_fbrd));
p.uartibrd().write_value(pac::uart::regs::Uartibrd(baud_ibrd));
p.uartfbrd().write_value(pac::uart::regs::Uartfbrd(baud_fbrd));
p.uartlcr_h().write(|w| {
w.set_wlen(config.data_bits - 5);

View file

@ -1,10 +1,10 @@
use std::collections::{HashMap, HashSet};
use std::fmt::Write as _;
use std::path::PathBuf;
use std::{env, fs};
use proc_macro2::TokenStream;
use quote::{format_ident, quote};
use std::collections::{HashMap, HashSet};
use std::env;
use std::fmt::Write as _;
use std::fs;
use std::path::PathBuf;
use stm32_metapac::metadata::METADATA;
fn main() {
@ -116,10 +116,7 @@ fn main() {
continue;
}
for irq in p.interrupts {
dma_irqs
.entry(irq.interrupt)
.or_default()
.push((p.name, irq.signal));
dma_irqs.entry(irq.interrupt).or_default().push((p.name, irq.signal));
}
}
}
@ -128,9 +125,7 @@ fn main() {
for (irq, channels) in dma_irqs {
let irq = format_ident!("{}", irq);
let channels = channels
.iter()
.map(|(dma, ch)| format_ident!("{}_{}", dma, ch));
let channels = channels.iter().map(|(dma, ch)| format_ident!("{}_{}", dma, ch));
g.extend(quote! {
#[crate::interrupt]
@ -147,9 +142,7 @@ fn main() {
for p in METADATA.peripherals {
// generating RccPeripheral impl for H7 ADC3 would result in bad frequency
if !singletons.contains(&p.name.to_string())
|| (p.name == "ADC3" && METADATA.line.starts_with("STM32H7"))
{
if !singletons.contains(&p.name.to_string()) || (p.name == "ADC3" && METADATA.line.starts_with("STM32H7")) {
continue;
}
@ -568,12 +561,7 @@ fn main() {
let mut pins_table: Vec<Vec<String>> = Vec::new();
let mut dma_channels_table: Vec<Vec<String>> = Vec::new();
let gpio_base = METADATA
.peripherals
.iter()
.find(|p| p.name == "GPIOA")
.unwrap()
.address as u32;
let gpio_base = METADATA.peripherals.iter().find(|p| p.name == "GPIOA").unwrap().address as u32;
let gpio_stride = 0x400;
for p in METADATA.peripherals {
@ -618,11 +606,7 @@ fn main() {
for ch in METADATA.dma_channels {
let mut row = Vec::new();
let dma_peri = METADATA
.peripherals
.iter()
.find(|p| p.name == ch.dma)
.unwrap();
let dma_peri = METADATA.peripherals.iter().find(|p| p.name == ch.dma).unwrap();
let bi = dma_peri.registers.as_ref().unwrap();
let num;
@ -649,10 +633,7 @@ fn main() {
row.push(num.to_string());
if let Some(dmamux) = &ch.dmamux {
let dmamux_channel = ch.dmamux_channel.unwrap();
row.push(format!(
"{{dmamux: {}, dmamux_channel: {}}}",
dmamux, dmamux_channel
));
row.push(format!("{{dmamux: {}, dmamux_channel: {}}}", dmamux, dmamux_channel));
} else {
row.push("{}".to_string());
}
@ -709,11 +690,7 @@ fn main() {
};
if let Some(core) = core_name {
println!(
"cargo:rustc-cfg={}_{}",
&chip_name[..chip_name.len() - 2],
core
);
println!("cargo:rustc-cfg={}_{}", &chip_name[..chip_name.len() - 2], core);
} else {
println!("cargo:rustc-cfg={}", &chip_name[..chip_name.len() - 2]);
}

View file

@ -1,10 +1,12 @@
use core::marker::PhantomData;
use embassy_hal_common::unborrow;
use embedded_hal_02::blocking::delay::DelayUs;
use crate::adc::{AdcPin, Instance};
use crate::rcc::get_freqs;
use crate::time::Hertz;
use crate::Unborrow;
use core::marker::PhantomData;
use embassy_hal_common::unborrow;
use embedded_hal_02::blocking::delay::DelayUs;
pub const VDDA_CALIB_MV: u32 = 3300;
pub const ADC_MAX: u32 = (1 << 12) - 1;

View file

@ -1,9 +1,11 @@
use core::marker::PhantomData;
use embassy_hal_common::unborrow;
use embedded_hal_02::blocking::delay::DelayUs;
use crate::adc::{AdcPin, Instance};
use crate::time::Hertz;
use crate::Unborrow;
use core::marker::PhantomData;
use embassy_hal_common::unborrow;
use embedded_hal_02::blocking::delay::DelayUs;
pub const VDDA_CALIB_MV: u32 = 3000;
@ -132,9 +134,7 @@ impl Prescaler {
2..=3 => Self::Div4,
4..=5 => Self::Div6,
6..=7 => Self::Div8,
_ => panic!(
"Selected PCLK2 frequency is too high for ADC with largest possible prescaler."
),
_ => panic!("Selected PCLK2 frequency is too high for ADC with largest possible prescaler."),
}
}
@ -165,9 +165,7 @@ where
let presc = unsafe { Prescaler::from_pclk2(crate::rcc::get_freqs().apb2) };
unsafe {
T::common_regs()
.ccr()
.modify(|w| w.set_adcpre(presc.adcpre()));
T::common_regs().ccr().modify(|w| w.set_adcpre(presc.adcpre()));
}
unsafe {
@ -241,9 +239,7 @@ where
pin.set_as_analog();
// Configure ADC
T::regs()
.cr1()
.modify(|reg| reg.set_res(self.resolution.res()));
T::regs().cr1().modify(|reg| reg.set_res(self.resolution.res()));
// Select channel
T::regs().sqr3().write(|reg| reg.set_sq(0, pin.channel()));

View file

@ -1,9 +1,11 @@
use crate::adc::{AdcPin, Instance};
use crate::Unborrow;
use core::marker::PhantomData;
use embassy_hal_common::unborrow;
use embedded_hal_02::blocking::delay::DelayUs;
use crate::adc::{AdcPin, Instance};
use crate::Unborrow;
pub const VDDA_CALIB_MV: u32 = 3000;
/// Sadly we cannot use `RccPeripheral::enable` since devices are quite inconsistent ADC clock
@ -369,13 +371,9 @@ impl<'d, T: Instance> Adc<'d, T> {
// Configure ADC
#[cfg(not(stm32g0))]
T::regs()
.cfgr()
.modify(|reg| reg.set_res(self.resolution.res()));
T::regs().cfgr().modify(|reg| reg.set_res(self.resolution.res()));
#[cfg(stm32g0)]
T::regs()
.cfgr1()
.modify(|reg| reg.set_res(self.resolution.res()));
T::regs().cfgr1().modify(|reg| reg.set_res(self.resolution.res()));
// Configure channel
Self::set_channel_sample_time(pin.channel(), self.sample_time);
@ -384,9 +382,7 @@ impl<'d, T: Instance> Adc<'d, T> {
#[cfg(not(stm32g0))]
T::regs().sqr1().write(|reg| reg.set_sq(0, pin.channel()));
#[cfg(stm32g0)]
T::regs()
.chselr()
.write(|reg| reg.set_chsel(pin.channel() as u32));
T::regs().chselr().write(|reg| reg.set_chsel(pin.channel() as u32));
// Some models are affected by an erratum:
// If we perform conversions slower than 1 kHz, the first read ADC value can be
@ -407,9 +403,7 @@ impl<'d, T: Instance> Adc<'d, T> {
#[cfg(stm32g0)]
unsafe fn set_channel_sample_time(_ch: u8, sample_time: SampleTime) {
T::regs()
.smpr()
.modify(|reg| reg.set_smp1(sample_time.sample_time()));
T::regs().smpr().modify(|reg| reg.set_smp1(sample_time.sample_time()));
}
#[cfg(not(stm32g0))]

View file

@ -1,16 +1,13 @@
use core::marker::PhantomData;
use crate::time::{Hertz, U32Ext};
use crate::Unborrow;
use atomic_polyfill::AtomicU8;
use atomic_polyfill::Ordering;
use atomic_polyfill::{AtomicU8, Ordering};
use embedded_hal_02::blocking::delay::DelayUs;
use pac::adc::vals::{Adcaldif, Boost, Difsel, Exten, Pcsel};
use pac::adccommon::vals::Presc;
use crate::pac;
use super::{AdcPin, Instance};
use crate::time::{Hertz, U32Ext};
use crate::{pac, Unborrow};
pub enum Resolution {
SixteenBit,
@ -333,9 +330,7 @@ impl<'d, T: Instance + crate::rcc::RccPeripheral> Adc<'d, T> {
let prescaler = Prescaler::from_ker_ck(T::frequency());
unsafe {
T::common_regs()
.ccr()
.modify(|w| w.set_presc(prescaler.presc()));
T::common_regs().ccr().modify(|w| w.set_presc(prescaler.presc()));
}
let frequency = Hertz(T::frequency().0 / prescaler.divisor());
@ -509,9 +504,7 @@ impl<'d, T: Instance + crate::rcc::RccPeripheral> Adc<'d, T> {
unsafe fn read_channel(&mut self, channel: u8) -> u16 {
// Configure ADC
T::regs()
.cfgr()
.modify(|reg| reg.set_res(self.resolution.res()));
T::regs().cfgr().modify(|reg| reg.set_res(self.resolution.res()));
// Configure channel
Self::set_channel_sample_time(channel, self.sample_time);

View file

@ -1,13 +1,12 @@
use core::marker::PhantomData;
use core::ops::{Deref, DerefMut};
use crate::Unborrow;
pub use bxcan;
use embassy_hal_common::unborrow;
use crate::gpio::sealed::AFType;
use crate::{peripherals, rcc::RccPeripheral};
pub use bxcan;
use crate::rcc::RccPeripheral;
use crate::{peripherals, Unborrow};
pub struct Can<'d, T: Instance + bxcan::Instance> {
phantom: PhantomData<&'d mut T>,

View file

@ -1,10 +1,11 @@
use core::marker::PhantomData;
use embassy_hal_common::unborrow;
use crate::pac::CRC as PAC_CRC;
use crate::peripherals::CRC;
use crate::rcc::sealed::RccPeripheral;
use crate::Unborrow;
use embassy_hal_common::unborrow;
pub struct Crc<'d> {
_peripheral: CRC,

View file

@ -1,11 +1,12 @@
use core::marker::PhantomData;
use embassy_hal_common::unborrow;
use crate::pac::crc::vals;
use crate::pac::CRC as PAC_CRC;
use crate::peripherals::CRC;
use crate::rcc::sealed::RccPeripheral;
use crate::Unborrow;
use embassy_hal_common::unborrow;
pub struct Crc<'d> {
_peripheral: CRC,

View file

@ -3,9 +3,10 @@
#[cfg_attr(dac_v1, path = "v1.rs")]
#[cfg_attr(dac_v2, path = "v2.rs")]
mod _version;
use crate::peripherals;
pub use _version::*;
use crate::peripherals;
pub(crate) mod sealed {
pub trait Instance {
fn regs() -> &'static crate::pac::dac::Dac;

View file

@ -1,8 +1,10 @@
use core::marker::PhantomData;
use embassy_hal_common::unborrow;
use crate::dac::{DacPin, Instance};
use crate::pac::dac;
use crate::Unborrow;
use core::marker::PhantomData;
use embassy_hal_common::unborrow;
#[derive(Debug, Copy, Clone, Eq, PartialEq)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
@ -93,23 +95,14 @@ pub struct Dac<'d, T: Instance> {
macro_rules! enable {
($enable_reg:ident, $enable_field:ident, $reset_reg:ident, $reset_field:ident) => {
crate::pac::RCC
.$enable_reg()
.modify(|w| w.$enable_field(true));
crate::pac::RCC
.$reset_reg()
.modify(|w| w.$reset_field(true));
crate::pac::RCC
.$reset_reg()
.modify(|w| w.$reset_field(false));
crate::pac::RCC.$enable_reg().modify(|w| w.$enable_field(true));
crate::pac::RCC.$reset_reg().modify(|w| w.$reset_field(true));
crate::pac::RCC.$reset_reg().modify(|w| w.$reset_field(false));
};
}
impl<'d, T: Instance> Dac<'d, T> {
pub fn new_1ch(
peri: impl Unborrow<Target = T> + 'd,
_ch1: impl Unborrow<Target = impl DacPin<T, 1>> + 'd,
) -> Self {
pub fn new_1ch(peri: impl Unborrow<Target = T> + 'd, _ch1: impl Unborrow<Target = impl DacPin<T, 1>> + 'd) -> Self {
unborrow!(peri);
Self::new_inner(peri, 1)
}

View file

@ -1,13 +1,14 @@
use core::marker::PhantomData;
use core::task::Poll;
use crate::interrupt::{Interrupt, InterruptExt};
use crate::Unborrow;
use embassy::waitqueue::AtomicWaker;
use embassy_hal_common::unborrow;
use futures::future::poll_fn;
use crate::gpio::{sealed::AFType, Speed};
use crate::gpio::sealed::AFType;
use crate::gpio::Speed;
use crate::interrupt::{Interrupt, InterruptExt};
use crate::Unborrow;
/// The level on the VSync pin when the data is not valid on the parallel interface.
#[derive(Clone, Copy, PartialEq)]
@ -466,14 +467,7 @@ where
let src = r.dr().ptr() as *mut u32;
unsafe {
channel.start_double_buffered_read(
request,
src,
m0ar,
m1ar,
chunk_size,
TransferOptions::default(),
);
channel.start_double_buffered_read(request, src, m0ar, m1ar, chunk_size, TransferOptions::default());
}
let mut last_chunk_set_for_transfer = false;

View file

@ -3,16 +3,15 @@
use core::sync::atomic::{fence, Ordering};
use core::task::Waker;
use crate::interrupt::{Interrupt, InterruptExt};
use embassy::waitqueue::AtomicWaker;
use super::{TransferOptions, Word, WordSize};
use crate::_generated::BDMA_CHANNEL_COUNT;
use crate::dma::Request;
use crate::interrupt::{Interrupt, InterruptExt};
use crate::pac;
use crate::pac::bdma::vals;
use super::{TransferOptions, Word, WordSize};
impl From<WordSize> for vals::Size {
fn from(raw: WordSize) -> Self {
match raw {
@ -185,14 +184,8 @@ mod low_level_api {
#[cfg(dmamux)] dmamux_regs: pac::dmamux::Dmamux,
#[cfg(dmamux)] dmamux_ch_num: u8,
) {
assert!(
options.mburst == crate::dma::Burst::Single,
"Burst mode not supported"
);
assert!(
options.pburst == crate::dma::Burst::Single,
"Burst mode not supported"
);
assert!(options.mburst == crate::dma::Burst::Single, "Burst mode not supported");
assert!(options.pburst == crate::dma::Burst::Single, "Burst mode not supported");
assert!(
options.flow_ctrl == crate::dma::FlowControl::Dma,
"Peripheral flow control not supported"
@ -206,10 +199,7 @@ mod low_level_api {
super::super::dmamux::configure_dmamux(dmamux_regs, dmamux_ch_num, request);
#[cfg(bdma_v2)]
critical_section::with(|_| {
dma.cselr()
.modify(|w| w.set_cs(channel_number as _, request))
});
critical_section::with(|_| dma.cselr().modify(|w| w.set_cs(channel_number as _, request)));
// "Preceding reads and writes cannot be moved past subsequent writes."
fence(Ordering::SeqCst);
@ -279,10 +269,7 @@ mod low_level_api {
let cr = dma.ch(channel_num).cr();
if isr.teif(channel_num) {
panic!(
"DMA: error on BDMA@{:08x} channel {}",
dma.0 as u32, channel_num
);
panic!("DMA: error on BDMA@{:08x} channel {}", dma.0 as u32, channel_num);
}
if isr.tcif(channel_num) && cr.read().tcie() {
cr.write(|_| ()); // Disable channel interrupts with the default value.

View file

@ -1,15 +1,13 @@
use core::sync::atomic::{fence, Ordering};
use core::task::Waker;
use crate::interrupt::{Interrupt, InterruptExt};
use embassy::waitqueue::AtomicWaker;
use crate::_generated::DMA_CHANNEL_COUNT;
use crate::interrupt;
use crate::pac;
use crate::pac::dma::{regs, vals};
use super::{Burst, FlowControl, Request, TransferOptions, Word, WordSize};
use crate::_generated::DMA_CHANNEL_COUNT;
use crate::interrupt::{Interrupt, InterruptExt};
use crate::pac::dma::{regs, vals};
use crate::{interrupt, pac};
impl From<WordSize> for vals::Size {
fn from(raw: WordSize) -> Self {
@ -407,10 +405,7 @@ mod low_level_api {
let isr = dma.isr(channel_num / 4).read();
if isr.teif(channel_num % 4) {
panic!(
"DMA: error on DMA@{:08x} channel {}",
dma.0 as u32, channel_num
);
panic!("DMA: error on DMA@{:08x} channel {}", dma.0 as u32, channel_num);
}
if isr.tcif(channel_num % 4) && cr.read().tcie() {
@ -418,8 +413,7 @@ mod low_level_api {
cr.write(|_| ()); // Disable channel with the default value.
} else {
// for double buffered mode, clear TCIF flag but do not stop the transfer
dma.ifcr(channel_num / 4)
.write(|w| w.set_tcif(channel_num % 4, true));
dma.ifcr(channel_num / 4).write(|w| w.set_tcif(channel_num % 4, true));
}
STATE.channels[state_index].waker.wake();
}

View file

@ -1,13 +1,8 @@
#![macro_use]
use crate::pac;
use crate::peripherals;
use crate::{pac, peripherals};
pub(crate) unsafe fn configure_dmamux(
dmamux_regs: pac::dmamux::Dmamux,
dmamux_ch_num: u8,
request: u8,
) {
pub(crate) unsafe fn configure_dmamux(dmamux_regs: pac::dmamux::Dmamux, dmamux_ch_num: u8, request: u8) {
let ch_mux_regs = dmamux_regs.ccr(dmamux_ch_num as _);
ch_mux_regs.write(|reg| {
reg.set_nbreq(0);

View file

@ -1,15 +1,13 @@
use core::sync::atomic::{fence, Ordering};
use core::task::Waker;
use crate::interrupt::{Interrupt, InterruptExt};
use embassy::waitqueue::AtomicWaker;
use crate::_generated::GPDMA_CHANNEL_COUNT;
use crate::interrupt;
use crate::pac;
use crate::pac::gpdma::{vals, Gpdma};
use super::{Request, TransferOptions, Word, WordSize};
use crate::_generated::GPDMA_CHANNEL_COUNT;
use crate::interrupt::{Interrupt, InterruptExt};
use crate::pac::gpdma::{vals, Gpdma};
use crate::{interrupt, pac};
impl From<WordSize> for vals::ChTr1Dw {
fn from(raw: WordSize) -> Self {

View file

@ -7,18 +7,18 @@ mod dmamux;
#[cfg(gpdma)]
mod gpdma;
#[cfg(dmamux)]
pub use dmamux::*;
use crate::Unborrow;
use core::future::Future;
use core::marker::PhantomData;
use core::mem;
use core::pin::Pin;
use core::task::Waker;
use core::task::{Context, Poll};
use core::task::{Context, Poll, Waker};
#[cfg(dmamux)]
pub use dmamux::*;
use embassy_hal_common::unborrow;
use crate::Unborrow;
#[cfg(feature = "unstable-pac")]
pub mod low_level {
pub use super::transfers::*;
@ -249,15 +249,7 @@ mod transfers {
) -> impl Future<Output = ()> + 'a {
unborrow!(channel);
unsafe {
channel.start_write_repeated::<W>(
request,
repeated,
count,
reg_addr,
Default::default(),
)
};
unsafe { channel.start_write_repeated::<W>(request, repeated, count, reg_addr, Default::default()) };
Transfer::new(channel)
}

View file

@ -51,10 +51,7 @@ unsafe impl PHY for GenericSMI {
Self::smi_write_ext(sm, PHY_REG_WUCSR, 0);
// Enable auto-negotiation
sm.smi_write(
PHY_REG_BCR,
PHY_REG_BCR_AN | PHY_REG_BCR_ANRST | PHY_REG_BCR_100M,
);
sm.smi_write(PHY_REG_BCR, PHY_REG_BCR_AN | PHY_REG_BCR_ANRST | PHY_REG_BCR_100M);
}
fn poll_link<S: StationManagement>(sm: &mut S) -> bool {

View file

@ -4,33 +4,30 @@ use core::marker::PhantomData;
use core::sync::atomic::{fence, Ordering};
use core::task::Waker;
use crate::Unborrow;
use embassy::waitqueue::AtomicWaker;
use embassy_cortex_m::peripheral::{PeripheralMutex, PeripheralState, StateStorage};
use embassy_hal_common::unborrow;
use embassy_net::{Device, DeviceCapabilities, LinkState, PacketBuf, MTU};
use crate::gpio::sealed::Pin as __GpioPin;
use crate::gpio::{sealed::AFType, AnyPin, Speed};
use crate::gpio::sealed::{AFType, Pin as __GpioPin};
use crate::gpio::{AnyPin, Speed};
#[cfg(eth_v1a)]
use crate::pac::AFIO;
#[cfg(any(eth_v1b, eth_v1c))]
use crate::pac::SYSCFG;
use crate::pac::{ETH, RCC};
use crate::Unborrow;
mod descriptors;
mod rx_desc;
mod tx_desc;
use super::*;
use descriptors::DescriptorRing;
use stm32_metapac::eth::vals::{
Apcs, Cr, Dm, DmaomrSr, Fes, Ftf, Ifg, MbProgress, Mw, Pbl, Rsf, St, Tsf,
};
use stm32_metapac::eth::vals::{Apcs, Cr, Dm, DmaomrSr, Fes, Ftf, Ifg, MbProgress, Mw, Pbl, Rsf, St, Tsf};
pub struct State<'d, T: Instance, const TX: usize, const RX: usize>(
StateStorage<Inner<'d, T, TX, RX>>,
);
use super::*;
pub struct State<'d, T: Instance, const TX: usize, const RX: usize>(StateStorage<Inner<'d, T, TX, RX>>);
impl<'d, T: Instance, const TX: usize, const RX: usize> State<'d, T, TX, RX> {
pub fn new() -> Self {
Self(StateStorage::new())
@ -300,9 +297,7 @@ unsafe impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> StationMa
}
}
impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> Device
for Ethernet<'d, T, P, TX, RX>
{
impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> Device for Ethernet<'d, T, P, TX, RX> {
fn is_transmit_ready(&mut self) -> bool {
self.state.with(|s| s.desc_ring.tx.available())
}
@ -339,9 +334,7 @@ impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> Device
}
}
impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> Drop
for Ethernet<'d, T, P, TX, RX>
{
impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> Drop for Ethernet<'d, T, P, TX, RX> {
fn drop(&mut self) {
// NOTE(unsafe) We have `&mut self` and the interrupt doesn't use this registers
unsafe {

View file

@ -59,8 +59,7 @@ impl RDes {
//
// Contains first buffer of packet AND contains last buf of
// packet AND no errors
(self.rdes0.get() & (RXDESC_0_ES | RXDESC_0_FS | RXDESC_0_LS))
== (RXDESC_0_FS | RXDESC_0_LS)
(self.rdes0.get() & (RXDESC_0_ES | RXDESC_0_FS | RXDESC_0_LS)) == (RXDESC_0_FS | RXDESC_0_LS)
}
/// Return true if this RDes is not currently owned by the DMA
@ -72,8 +71,7 @@ impl RDes {
/// Configures the reception buffer address and length and passed descriptor ownership to the DMA
#[inline(always)]
pub fn set_ready(&mut self, buf_addr: u32, buf_len: usize) {
self.rdes1
.set(self.rdes1.get() | (buf_len as u32) & RXDESC_1_RBS_MASK);
self.rdes1.set(self.rdes1.get() | (buf_len as u32) & RXDESC_1_RBS_MASK);
self.rdes2.set(buf_addr);
// "Preceding reads and writes cannot be moved past subsequent writes."
@ -220,11 +218,7 @@ impl<const N: usize> RDesRing<N> {
// We already have fences in `set_owned`, which is called in `setup`
// Start receive
unsafe {
ETH.ethernet_dma()
.dmaomr()
.modify(|w| w.set_sr(DmaomrSr::STARTED))
};
unsafe { ETH.ethernet_dma().dmaomr().modify(|w| w.set_sr(DmaomrSr::STARTED)) };
self.demand_poll();
}

View file

@ -100,8 +100,7 @@ impl TDes {
// set up as a part fo the ring buffer - configures the tdes
pub fn setup(&mut self, next: Option<&Self>) {
// Defer this initialization to this function, so we can have `RingEntry` on bss.
self.tdes0
.set(TXDESC_0_TCH | TXDESC_0_IOC | TXDESC_0_FS | TXDESC_0_LS);
self.tdes0.set(TXDESC_0_TCH | TXDESC_0_IOC | TXDESC_0_FS | TXDESC_0_LS);
match next {
Some(next) => self.set_buffer2(next as *const TDes as *const u8),
None => {
@ -169,11 +168,7 @@ impl<const N: usize> TDesRing<N> {
// volatiles
// Start transmission
unsafe {
ETH.ethernet_dma()
.dmaomr()
.modify(|w| w.set_st(St::STARTED))
};
unsafe { ETH.ethernet_dma().dmaomr().modify(|w| w.set_st(St::STARTED)) };
}
/// Return true if a TDes is available for use

View file

@ -101,11 +101,9 @@ impl<const N: usize> TDesRing<N> {
unsafe {
let dma = ETH.ethernet_dma();
dma.dmactx_dlar()
.write(|w| w.0 = &self.td as *const _ as u32);
dma.dmactx_dlar().write(|w| w.0 = &self.td as *const _ as u32);
dma.dmactx_rlr().write(|w| w.set_tdrl((N as u16) - 1));
dma.dmactx_dtpr()
.write(|w| w.0 = &self.td[0] as *const _ as u32);
dma.dmactx_dtpr().write(|w| w.0 = &self.td[0] as *const _ as u32);
}
}
@ -127,8 +125,7 @@ impl<const N: usize> TDesRing<N> {
// Read format
td.tdes0.set(address);
td.tdes2
.set(pkt_len as u32 & EMAC_TDES2_B1L | EMAC_TDES2_IOC);
td.tdes2.set(pkt_len as u32 & EMAC_TDES2_B1L | EMAC_TDES2_IOC);
// FD: Contains first buffer of packet
// LD: Contains last buffer of packet
@ -225,8 +222,7 @@ impl RDes {
#[inline(always)]
pub fn set_ready(&mut self, buf_addr: u32) {
self.rdes0.set(buf_addr);
self.rdes3
.set(EMAC_RDES3_BUF1V | EMAC_RDES3_IOC | EMAC_DES3_OWN);
self.rdes3.set(EMAC_RDES3_BUF1V | EMAC_RDES3_IOC | EMAC_DES3_OWN);
}
}

View file

@ -2,23 +2,22 @@ use core::marker::PhantomData;
use core::sync::atomic::{fence, Ordering};
use core::task::Waker;
use crate::Unborrow;
use embassy::waitqueue::AtomicWaker;
use embassy_cortex_m::peripheral::{PeripheralMutex, PeripheralState, StateStorage};
use embassy_hal_common::unborrow;
use embassy_net::{Device, DeviceCapabilities, LinkState, PacketBuf, MTU};
use crate::gpio::sealed::Pin as _;
use crate::gpio::{sealed::AFType, AnyPin, Speed};
use crate::gpio::sealed::{AFType, Pin as _};
use crate::gpio::{AnyPin, Speed};
use crate::pac::{ETH, RCC, SYSCFG};
use crate::Unborrow;
mod descriptors;
use super::*;
use descriptors::DescriptorRing;
pub struct State<'d, T: Instance, const TX: usize, const RX: usize>(
StateStorage<Inner<'d, T, TX, RX>>,
);
use super::*;
pub struct State<'d, T: Instance, const TX: usize, const RX: usize>(StateStorage<Inner<'d, T, TX, RX>>);
impl<'d, T: Instance, const TX: usize, const RX: usize> State<'d, T, TX, RX> {
pub fn new() -> Self {
Self(StateStorage::new())
@ -234,9 +233,7 @@ unsafe impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> StationMa
}
}
impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> Device
for Ethernet<'d, T, P, TX, RX>
{
impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> Device for Ethernet<'d, T, P, TX, RX> {
fn is_transmit_ready(&mut self) -> bool {
self.state.with(|s| s.desc_ring.tx.available())
}
@ -273,9 +270,7 @@ impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> Device
}
}
impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> Drop
for Ethernet<'d, T, P, TX, RX>
{
impl<'d, T: Instance, P: PHY, const TX: usize, const RX: usize> Drop for Ethernet<'d, T, P, TX, RX> {
fn drop(&mut self) {
// NOTE(unsafe) We have `&mut self` and the interrupt doesn't use this registers
unsafe {

View file

@ -1,17 +1,15 @@
use crate::Unborrow;
use core::future::Future;
use core::marker::PhantomData;
use core::pin::Pin;
use core::task::{Context, Poll};
use embassy::waitqueue::AtomicWaker;
use embassy_hal_common::unsafe_impl_unborrow;
use crate::gpio::{AnyPin, Input, Pin as GpioPin};
use crate::interrupt;
use crate::pac;
use crate::pac::exti::regs::Lines;
use crate::pac::EXTI;
use crate::peripherals;
use crate::{interrupt, pac, peripherals, Unborrow};
const EXTI_COUNT: usize = 16;
const NEW_AW: AtomicWaker = AtomicWaker::new();
@ -130,9 +128,10 @@ impl<'d, T: GpioPin> ExtiInput<'d, T> {
}
mod eh02 {
use super::*;
use core::convert::Infallible;
use super::*;
impl<'d, T: GpioPin> embedded_hal_02::digital::v2::InputPin for ExtiInput<'d, T> {
type Error = Infallible;
@ -148,9 +147,10 @@ mod eh02 {
#[cfg(feature = "unstable-traits")]
mod eh1 {
use super::*;
use core::convert::Infallible;
use super::*;
impl<'d, T: GpioPin> embedded_hal_1::digital::ErrorType for ExtiInput<'d, T> {
type Error = Infallible;
}
@ -212,9 +212,7 @@ impl<'a> ExtiInputFuture<'a> {
fn new(pin: u8, port: u8, rising: bool, falling: bool) -> Self {
critical_section::with(|_| unsafe {
let pin = pin as usize;
exticr_regs()
.exticr(pin / 4)
.modify(|w| w.set_exti(pin % 4, port));
exticr_regs().exticr(pin / 4).modify(|w| w.set_exti(pin % 4, port));
EXTI.rtsr(0).modify(|w| w.set_line(pin, rising));
EXTI.ftsr(0).modify(|w| w.set_line(pin, falling));
@ -366,8 +364,7 @@ macro_rules! enable_irq {
/// safety: must be called only once
pub(crate) unsafe fn init() {
use crate::interrupt::Interrupt;
use crate::interrupt::InterruptExt;
use crate::interrupt::{Interrupt, InterruptExt};
foreach_exti_irq!(enable_irq);

View file

@ -20,10 +20,7 @@ pub(crate) unsafe fn blocking_write(offset: u32, buf: &[u8]) -> Result<(), Error
let mut ret: Result<(), Error> = Ok(());
let mut offset = offset;
for chunk in buf.chunks(2) {
write_volatile(
offset as *mut u16,
u16::from_le_bytes(chunk[0..2].try_into().unwrap()),
);
write_volatile(offset as *mut u16, u16::from_le_bytes(chunk[0..2].try_into().unwrap()));
offset += chunk.len() as u32;
ret = blocking_wait_ready();

View file

@ -26,10 +26,7 @@ pub(crate) unsafe fn blocking_write(offset: u32, buf: &[u8]) -> Result<(), Error
let mut offset = offset;
for chunk in buf.chunks(super::WRITE_SIZE) {
for val in chunk.chunks(4) {
write_volatile(
offset as *mut u32,
u32::from_le_bytes(val[0..4].try_into().unwrap()),
);
write_volatile(offset as *mut u32, u32::from_le_bytes(val[0..4].try_into().unwrap()));
offset += val.len() as u32;
// prevents parallelism errors

View file

@ -28,8 +28,7 @@ pub(crate) unsafe fn unlock() {
}
pub(crate) unsafe fn blocking_write(offset: u32, buf: &[u8]) -> Result<(), Error> {
let bank = if !is_dual_bank() || (offset - super::FLASH_BASE as u32) < SECOND_BANK_OFFSET as u32
{
let bank = if !is_dual_bank() || (offset - super::FLASH_BASE as u32) < SECOND_BANK_OFFSET as u32 {
pac::FLASH.bank(0)
} else {
pac::FLASH.bank(1)
@ -46,10 +45,7 @@ pub(crate) unsafe fn blocking_write(offset: u32, buf: &[u8]) -> Result<(), Error
'outer: for chunk in buf.chunks(super::WRITE_SIZE) {
for val in chunk.chunks(4) {
trace!("Writing at {:x}", offset);
write_volatile(
offset as *mut u32,
u32::from_le_bytes(val[0..4].try_into().unwrap()),
);
write_volatile(offset as *mut u32, u32::from_le_bytes(val[0..4].try_into().unwrap()));
offset += val.len() as u32;
ret = blocking_wait_ready(bank);

View file

@ -42,10 +42,7 @@ pub(crate) unsafe fn blocking_write(offset: u32, buf: &[u8]) -> Result<(), Error
let mut offset = offset;
for chunk in buf.chunks(super::WRITE_SIZE) {
for val in chunk.chunks(4) {
write_volatile(
offset as *mut u32,
u32::from_le_bytes(val[0..4].try_into().unwrap()),
);
write_volatile(offset as *mut u32, u32::from_le_bytes(val[0..4].try_into().unwrap()));
offset += val.len() as u32;
}
@ -80,11 +77,7 @@ pub(crate) unsafe fn blocking_erase(from: u32, to: u32) -> Result<(), Error> {
let idx = (page - super::FLASH_BASE as u32) / super::ERASE_SIZE as u32;
#[cfg(flash_l4)]
let (idx, bank) = if idx > 255 {
(idx - 256, true)
} else {
(idx, false)
};
let (idx, bank) = if idx > 255 { (idx - 256, true) } else { (idx, false) };
pac::FLASH.cr().modify(|w| {
w.set_per(true);

View file

@ -1,17 +1,11 @@
use core::marker::PhantomData;
use embassy_hal_common::unborrow;
use embedded_storage::nor_flash::{ErrorType, NorFlash, NorFlashError, NorFlashErrorKind, ReadNorFlash};
pub use crate::pac::{ERASE_SIZE, ERASE_VALUE, FLASH_BASE, FLASH_SIZE, WRITE_SIZE};
use crate::peripherals::FLASH;
use crate::Unborrow;
use core::marker::PhantomData;
use embassy_hal_common::unborrow;
use embedded_storage::nor_flash::{
ErrorType, NorFlash, NorFlashError, NorFlashErrorKind, ReadNorFlash,
};
pub use crate::pac::ERASE_SIZE;
pub use crate::pac::ERASE_VALUE;
pub use crate::pac::FLASH_BASE;
pub use crate::pac::FLASH_SIZE;
pub use crate::pac::WRITE_SIZE;
const FLASH_END: usize = FLASH_BASE + FLASH_SIZE;
#[cfg_attr(any(flash_wl, flash_wb, flash_l0, flash_l1, flash_l4), path = "l.rs")]

View file

@ -1,9 +1,10 @@
use crate::Unborrow;
use core::marker::PhantomData;
use embassy_hal_common::unborrow;
use crate::gpio::sealed::AFType;
use crate::gpio::{Pull, Speed};
use crate::Unborrow;
mod pins;
pub use pins::*;

View file

@ -1,12 +1,11 @@
#![macro_use]
use crate::Unborrow;
use core::convert::Infallible;
use core::marker::PhantomData;
use embassy_hal_common::{unborrow, unsafe_impl_unborrow};
use crate::pac;
use crate::pac::gpio::{self, vals};
use crate::peripherals;
use crate::{pac, peripherals, Unborrow};
/// Pull setting for an input.
#[derive(Debug, Eq, PartialEq)]
@ -138,8 +137,7 @@ impl<'d, T: Pin> Drop for Input<'d, T> {
#[cfg(gpio_v1)]
{
let crlh = if n < 8 { 0 } else { 1 };
r.cr(crlh)
.modify(|w| w.set_cnf_in(n % 8, vals::CnfIn::FLOATING));
r.cr(crlh).modify(|w| w.set_cnf_in(n % 8, vals::CnfIn::FLOATING));
}
#[cfg(gpio_v2)]
r.pupdr().modify(|w| w.set_pupdr(n, vals::Pupdr::FLOATING));
@ -264,12 +262,7 @@ pub struct OutputOpenDrain<'d, T: Pin> {
impl<'d, T: Pin> OutputOpenDrain<'d, T> {
#[inline]
pub fn new(
pin: impl Unborrow<Target = T> + 'd,
initial_output: Level,
speed: Speed,
pull: Pull,
) -> Self {
pub fn new(pin: impl Unborrow<Target = T> + 'd, initial_output: Level, speed: Speed, pull: Pull) -> Self {
unborrow!(pin);
match initial_output {
@ -289,8 +282,7 @@ impl<'d, T: Pin> OutputOpenDrain<'d, T> {
Pull::None => {}
}
r.cr(crlh).modify(|w| w.set_mode(n % 8, speed.into()));
r.cr(crlh)
.modify(|w| w.set_cnf_out(n % 8, vals::CnfOut::OPENDRAIN));
r.cr(crlh).modify(|w| w.set_cnf_out(n % 8, vals::CnfOut::OPENDRAIN));
}
#[cfg(gpio_v2)]
{
@ -480,18 +472,12 @@ pub(crate) mod sealed {
block.afr(pin / 8).modify(|w| w.set_afr(pin % 8, af_num));
match af_type {
AFType::Input => {}
AFType::OutputPushPull => {
block.otyper().modify(|w| w.set_ot(pin, vals::Ot::PUSHPULL))
}
AFType::OutputOpenDrain => block
.otyper()
.modify(|w| w.set_ot(pin, vals::Ot::OPENDRAIN)),
AFType::OutputPushPull => block.otyper().modify(|w| w.set_ot(pin, vals::Ot::PUSHPULL)),
AFType::OutputOpenDrain => block.otyper().modify(|w| w.set_ot(pin, vals::Ot::OPENDRAIN)),
}
block.pupdr().modify(|w| w.set_pupdr(pin, pull.into()));
block
.moder()
.modify(|w| w.set_moder(pin, vals::Moder::ALTERNATE));
block.moder().modify(|w| w.set_moder(pin, vals::Moder::ALTERNATE));
}
#[inline]
@ -507,9 +493,7 @@ pub(crate) mod sealed {
});
}
#[cfg(gpio_v2)]
block
.moder()
.modify(|w| w.set_moder(pin, vals::Moder::ANALOG));
block.moder().modify(|w| w.set_moder(pin, vals::Moder::ANALOG));
}
/// Set the pin as "disconnected", ie doing nothing and consuming the lowest
@ -535,9 +519,7 @@ pub(crate) mod sealed {
}
#[cfg(gpio_v2)]
self.block()
.ospeedr()
.modify(|w| w.set_ospeedr(pin, speed.into()));
self.block().ospeedr().modify(|w| w.set_ospeedr(pin, speed.into()));
}
}
}
@ -623,10 +605,9 @@ pub(crate) unsafe fn init() {
}
mod eh02 {
use embedded_hal_02::digital::v2::{InputPin, OutputPin, StatefulOutputPin, ToggleableOutputPin};
use super::*;
use embedded_hal_02::digital::v2::{
InputPin, OutputPin, StatefulOutputPin, ToggleableOutputPin,
};
impl<'d, T: Pin> InputPin for Input<'d, T> {
type Error = Infallible;
@ -715,12 +696,11 @@ mod eh02 {
#[cfg(feature = "unstable-traits")]
mod eh1 {
use super::*;
use embedded_hal_1::digital::blocking::{
InputPin, OutputPin, StatefulOutputPin, ToggleableOutputPin,
};
use embedded_hal_1::digital::blocking::{InputPin, OutputPin, StatefulOutputPin, ToggleableOutputPin};
use embedded_hal_1::digital::ErrorType;
use super::*;
impl<'d, T: Pin> ErrorType for Input<'d, T> {
type Error = Infallible;
}

View file

@ -5,9 +5,10 @@ use crate::interrupt::Interrupt;
#[cfg_attr(i2c_v1, path = "v1.rs")]
#[cfg_attr(i2c_v2, path = "v2.rs")]
mod _version;
use crate::peripherals;
pub use _version::*;
use crate::peripherals;
#[derive(Debug)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
pub enum Error {

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