docs: embassy-rp rustdoc and refactoring

This commit is contained in:
Ulf Lilleengen 2023-12-19 10:11:19 +01:00
parent 08e9a4d84a
commit e45e3e76b5
10 changed files with 253 additions and 26 deletions

View file

@ -6,8 +6,8 @@ use core::slice;
use cyw43::SpiBusCyw43;
use embassy_rp::dma::Channel;
use embassy_rp::gpio::{Drive, Level, Output, Pin, Pull, SlewRate};
use embassy_rp::pio::{Common, Config, Direction, Instance, Irq, PioPin, ShiftDirection, StateMachine};
use embassy_rp::{pio_instr_util, Peripheral, PeripheralRef};
use embassy_rp::pio::{instr, Common, Config, Direction, Instance, Irq, PioPin, ShiftDirection, StateMachine};
use embassy_rp::{Peripheral, PeripheralRef};
use fixed::FixedU32;
use pio_proc::pio_asm;
@ -152,10 +152,10 @@ where
defmt::trace!("write={} read={}", write_bits, read_bits);
unsafe {
pio_instr_util::set_x(&mut self.sm, write_bits as u32);
pio_instr_util::set_y(&mut self.sm, read_bits as u32);
pio_instr_util::set_pindir(&mut self.sm, 0b1);
pio_instr_util::exec_jmp(&mut self.sm, self.wrap_target);
instr::set_x(&mut self.sm, write_bits as u32);
instr::set_y(&mut self.sm, read_bits as u32);
instr::set_pindir(&mut self.sm, 0b1);
instr::exec_jmp(&mut self.sm, self.wrap_target);
}
self.sm.set_enable(true);
@ -179,10 +179,10 @@ where
defmt::trace!("write={} read={}", write_bits, read_bits);
unsafe {
pio_instr_util::set_y(&mut self.sm, read_bits as u32);
pio_instr_util::set_x(&mut self.sm, write_bits as u32);
pio_instr_util::set_pindir(&mut self.sm, 0b1);
pio_instr_util::exec_jmp(&mut self.sm, self.wrap_target);
instr::set_y(&mut self.sm, read_bits as u32);
instr::set_x(&mut self.sm, write_bits as u32);
instr::set_pindir(&mut self.sm, 0b1);
instr::exec_jmp(&mut self.sm, self.wrap_target);
}
// self.cs.set_low();

View file

@ -6,6 +6,8 @@ The Embassy nRF HAL targets the Nordic Semiconductor nRF family of hardware. The
for many peripherals. The benefit of using the async APIs is that the HAL takes care of waiting for peripherals to
complete operations in low power mod and handling interrupts, so that applications can focus on more important matters.
NOTE: The Embassy HALs can be used both for non-async and async operations. For async, you can choose which runtime you want to use.
## EasyDMA considerations
On nRF chips, peripherals can use the so called EasyDMA feature to offload the task of interacting

23
embassy-rp/README.md Normal file
View file

@ -0,0 +1,23 @@
# Embassy RP HAL
HALs implement safe, idiomatic Rust APIs to use the hardware capabilities, so raw register manipulation is not needed.
The Embassy RP HAL targets the Raspberry Pi 2040 family of hardware. The HAL implements both blocking and async APIs
for many peripherals. The benefit of using the async APIs is that the HAL takes care of waiting for peripherals to
complete operations in low power mod and handling interrupts, so that applications can focus on more important matters.
NOTE: The Embassy HALs can be used both for non-async and async operations. For async, you can choose which runtime you want to use.
## Minimum supported Rust version (MSRV)
Embassy is guaranteed to compile on the latest stable Rust version at the time of release. It might compile with older versions but that may change in any new patch release.
## License
This work is licensed under either of
- Apache License, Version 2.0 ([LICENSE-APACHE](LICENSE-APACHE) or
<http://www.apache.org/licenses/LICENSE-2.0>)
- MIT license ([LICENSE-MIT](LICENSE-MIT) or <http://opensource.org/licenses/MIT>)
at your option.

View file

@ -1,3 +1,4 @@
//! Clock configuration for the RP2040
use core::arch::asm;
use core::marker::PhantomData;
use core::sync::atomic::{AtomicU16, AtomicU32, Ordering};
@ -44,6 +45,7 @@ static CLOCKS: Clocks = Clocks {
rtc: AtomicU16::new(0),
};
/// Enumeration of supported clock sources.
#[repr(u8)]
#[non_exhaustive]
#[derive(Clone, Copy, Debug, PartialEq, Eq)]
@ -57,15 +59,24 @@ pub enum PeriClkSrc {
// Gpin1 = ClkPeriCtrlAuxsrc::CLKSRC_GPIN1 as _ ,
}
/// CLock configuration.
#[non_exhaustive]
pub struct ClockConfig {
/// Ring oscillator configuration.
pub rosc: Option<RoscConfig>,
/// External oscillator configuration.
pub xosc: Option<XoscConfig>,
/// Reference clock configuration.
pub ref_clk: RefClkConfig,
/// System clock configuration.
pub sys_clk: SysClkConfig,
/// Peripheral clock source configuration.
pub peri_clk_src: Option<PeriClkSrc>,
/// USB clock configuration.
pub usb_clk: Option<UsbClkConfig>,
/// ADC clock configuration.
pub adc_clk: Option<AdcClkConfig>,
/// RTC clock configuration.
pub rtc_clk: Option<RtcClkConfig>,
// gpin0: Option<(u32, Gpin<'static, AnyPin>)>,
// gpin1: Option<(u32, Gpin<'static, AnyPin>)>,
@ -189,31 +200,46 @@ pub enum RoscRange {
TooHigh = pac::rosc::vals::FreqRange::TOOHIGH.0,
}
/// On-chip ring oscillator configuration.
pub struct RoscConfig {
/// Final frequency of the oscillator, after the divider has been applied.
/// The oscillator has a nominal frequency of 6.5MHz at medium range with
/// divider 16 and all drive strengths set to 0, other values should be
/// measured in situ.
pub hz: u32,
/// Oscillator range.
pub range: RoscRange,
/// Drive strength for oscillator.
pub drive_strength: [u8; 8],
/// Output divider.
pub div: u16,
}
/// Crystal oscillator configuration.
pub struct XoscConfig {
/// Final frequency of the oscillator.
pub hz: u32,
/// Configuring PLL for the system clock.
pub sys_pll: Option<PllConfig>,
/// Configuring PLL for the USB clock.
pub usb_pll: Option<PllConfig>,
/// Multiplier for the startup delay.
pub delay_multiplier: u32,
}
/// PLL configuration.
pub struct PllConfig {
/// Reference divisor.
pub refdiv: u8,
/// Feedback divisor.
pub fbdiv: u16,
/// Output divisor 1.
pub post_div1: u8,
/// Output divisor 2.
pub post_div2: u8,
}
/// Reference
pub struct RefClkConfig {
pub src: RefClkSrc,
pub div: u8,

View file

@ -1,5 +1,6 @@
#![no_std]
#![allow(async_fn_in_trait)]
#![doc = include_str!("../README.md")]
// This mod MUST go first, so that the others see its macros.
pub(crate) mod fmt;
@ -31,9 +32,7 @@ pub mod usb;
pub mod watchdog;
// PIO
// TODO: move `pio_instr_util` and `relocate` to inside `pio`
pub mod pio;
pub mod pio_instr_util;
pub(crate) mod relocate;
// Reexports
@ -302,11 +301,14 @@ fn install_stack_guard(stack_bottom: *mut usize) -> Result<(), ()> {
Ok(())
}
/// HAL configuration for RP.
pub mod config {
use crate::clocks::ClockConfig;
/// HAL configuration passed when initializing.
#[non_exhaustive]
pub struct Config {
/// Clock configuration.
pub clocks: ClockConfig,
}
@ -319,12 +321,18 @@ pub mod config {
}
impl Config {
/// Create a new configuration with the provided clock config.
pub fn new(clocks: ClockConfig) -> Self {
Self { clocks }
}
}
}
/// Initialize the `embassy-rp` HAL with the provided configuration.
///
/// This returns the peripheral singletons that can be used for creating drivers.
///
/// This should only be called once at startup, otherwise it panics.
pub fn init(config: config::Config) -> Peripherals {
// Do this first, so that it panics if user is calling `init` a second time
// before doing anything important.

View file

@ -1,7 +1,9 @@
//! Instructions controlling the PIO.
use pio::{InSource, InstructionOperands, JmpCondition, OutDestination, SetDestination};
use crate::pio::{Instance, StateMachine};
/// Set value of scratch register X.
pub unsafe fn set_x<PIO: Instance, const SM: usize>(sm: &mut StateMachine<PIO, SM>, value: u32) {
const OUT: u16 = InstructionOperands::OUT {
destination: OutDestination::X,
@ -12,6 +14,7 @@ pub unsafe fn set_x<PIO: Instance, const SM: usize>(sm: &mut StateMachine<PIO, S
sm.exec_instr(OUT);
}
/// Get value of scratch register X.
pub unsafe fn get_x<PIO: Instance, const SM: usize>(sm: &mut StateMachine<PIO, SM>) -> u32 {
const IN: u16 = InstructionOperands::IN {
source: InSource::X,
@ -22,6 +25,7 @@ pub unsafe fn get_x<PIO: Instance, const SM: usize>(sm: &mut StateMachine<PIO, S
sm.rx().pull()
}
/// Set value of scratch register Y.
pub unsafe fn set_y<PIO: Instance, const SM: usize>(sm: &mut StateMachine<PIO, SM>, value: u32) {
const OUT: u16 = InstructionOperands::OUT {
destination: OutDestination::Y,
@ -32,6 +36,7 @@ pub unsafe fn set_y<PIO: Instance, const SM: usize>(sm: &mut StateMachine<PIO, S
sm.exec_instr(OUT);
}
/// Get value of scratch register Y.
pub unsafe fn get_y<PIO: Instance, const SM: usize>(sm: &mut StateMachine<PIO, SM>) -> u32 {
const IN: u16 = InstructionOperands::IN {
source: InSource::Y,
@ -43,6 +48,7 @@ pub unsafe fn get_y<PIO: Instance, const SM: usize>(sm: &mut StateMachine<PIO, S
sm.rx().pull()
}
/// Set instruction for pindir destination.
pub unsafe fn set_pindir<PIO: Instance, const SM: usize>(sm: &mut StateMachine<PIO, SM>, data: u8) {
let set: u16 = InstructionOperands::SET {
destination: SetDestination::PINDIRS,
@ -52,6 +58,7 @@ pub unsafe fn set_pindir<PIO: Instance, const SM: usize>(sm: &mut StateMachine<P
sm.exec_instr(set);
}
/// Set instruction for pin destination.
pub unsafe fn set_pin<PIO: Instance, const SM: usize>(sm: &mut StateMachine<PIO, SM>, data: u8) {
let set: u16 = InstructionOperands::SET {
destination: SetDestination::PINS,
@ -61,6 +68,7 @@ pub unsafe fn set_pin<PIO: Instance, const SM: usize>(sm: &mut StateMachine<PIO,
sm.exec_instr(set);
}
/// Out instruction for pin destination.
pub unsafe fn set_out_pin<PIO: Instance, const SM: usize>(sm: &mut StateMachine<PIO, SM>, data: u32) {
const OUT: u16 = InstructionOperands::OUT {
destination: OutDestination::PINS,
@ -70,6 +78,8 @@ pub unsafe fn set_out_pin<PIO: Instance, const SM: usize>(sm: &mut StateMachine<
sm.tx().push(data);
sm.exec_instr(OUT);
}
/// Out instruction for pindir destination.
pub unsafe fn set_out_pindir<PIO: Instance, const SM: usize>(sm: &mut StateMachine<PIO, SM>, data: u32) {
const OUT: u16 = InstructionOperands::OUT {
destination: OutDestination::PINDIRS,
@ -80,6 +90,7 @@ pub unsafe fn set_out_pindir<PIO: Instance, const SM: usize>(sm: &mut StateMachi
sm.exec_instr(OUT);
}
/// Jump instruction to address.
pub unsafe fn exec_jmp<PIO: Instance, const SM: usize>(sm: &mut StateMachine<PIO, SM>, to_addr: u8) {
let jmp: u16 = InstructionOperands::JMP {
address: to_addr,

View file

@ -19,8 +19,11 @@ use crate::gpio::{self, AnyPin, Drive, Level, Pull, SlewRate};
use crate::interrupt::typelevel::{Binding, Handler, Interrupt};
use crate::pac::dma::vals::TreqSel;
use crate::relocate::RelocatedProgram;
use crate::{pac, peripherals, pio_instr_util, RegExt};
use crate::{pac, peripherals, RegExt};
pub mod instr;
/// Wakers for interrupts and FIFOs.
pub struct Wakers([AtomicWaker; 12]);
impl Wakers {
@ -38,6 +41,7 @@ impl Wakers {
}
}
/// FIFO config.
#[derive(Clone, Copy, PartialEq, Eq, Default, Debug)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
#[repr(u8)]
@ -51,6 +55,8 @@ pub enum FifoJoin {
TxOnly,
}
/// Shift direction.
#[allow(missing_docs)]
#[derive(Clone, Copy, PartialEq, Eq, Default, Debug)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
#[repr(u8)]
@ -60,6 +66,8 @@ pub enum ShiftDirection {
Left = 0,
}
/// Pin direction.
#[allow(missing_docs)]
#[derive(Clone, Copy, PartialEq, Eq, Debug)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
#[repr(u8)]
@ -68,12 +76,15 @@ pub enum Direction {
Out = 1,
}
/// Which fifo level to use in status check.
#[derive(Clone, Copy, PartialEq, Eq, Default, Debug)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
#[repr(u8)]
pub enum StatusSource {
#[default]
/// All-ones if TX FIFO level < N, otherwise all-zeroes.
TxFifoLevel = 0,
/// All-ones if RX FIFO level < N, otherwise all-zeroes.
RxFifoLevel = 1,
}
@ -81,6 +92,7 @@ const RXNEMPTY_MASK: u32 = 1 << 0;
const TXNFULL_MASK: u32 = 1 << 4;
const SMIRQ_MASK: u32 = 1 << 8;
/// Interrupt handler for PIO.
pub struct InterruptHandler<PIO: Instance> {
_pio: PhantomData<PIO>,
}
@ -105,6 +117,7 @@ pub struct FifoOutFuture<'a, 'd, PIO: Instance, const SM: usize> {
}
impl<'a, 'd, PIO: Instance, const SM: usize> FifoOutFuture<'a, 'd, PIO, SM> {
/// Create a new future waiting for TX-FIFO to become writable.
pub fn new(sm: &'a mut StateMachineTx<'d, PIO, SM>, value: u32) -> Self {
FifoOutFuture { sm_tx: sm, value }
}
@ -136,13 +149,14 @@ impl<'a, 'd, PIO: Instance, const SM: usize> Drop for FifoOutFuture<'a, 'd, PIO,
}
}
/// Future that waits for RX-FIFO to become readable
/// Future that waits for RX-FIFO to become readable.
#[must_use = "futures do nothing unless you `.await` or poll them"]
pub struct FifoInFuture<'a, 'd, PIO: Instance, const SM: usize> {
sm_rx: &'a mut StateMachineRx<'d, PIO, SM>,
}
impl<'a, 'd, PIO: Instance, const SM: usize> FifoInFuture<'a, 'd, PIO, SM> {
/// Create future that waits for RX-FIFO to become readable.
pub fn new(sm: &'a mut StateMachineRx<'d, PIO, SM>) -> Self {
FifoInFuture { sm_rx: sm }
}
@ -207,6 +221,7 @@ impl<'a, 'd, PIO: Instance> Drop for IrqFuture<'a, 'd, PIO> {
}
}
/// Type representing a PIO pin.
pub struct Pin<'l, PIO: Instance> {
pin: PeripheralRef<'l, AnyPin>,
pio: PhantomData<PIO>,
@ -226,7 +241,7 @@ impl<'l, PIO: Instance> Pin<'l, PIO> {
});
}
// Set the pin's slew rate.
/// Set the pin's slew rate.
#[inline]
pub fn set_slew_rate(&mut self, slew_rate: SlewRate) {
self.pin.pad_ctrl().modify(|w| {
@ -251,6 +266,7 @@ impl<'l, PIO: Instance> Pin<'l, PIO> {
});
}
/// Set the pin's input sync bypass.
pub fn set_input_sync_bypass<'a>(&mut self, bypass: bool) {
let mask = 1 << self.pin();
if bypass {
@ -260,28 +276,34 @@ impl<'l, PIO: Instance> Pin<'l, PIO> {
}
}
/// Get the underlying pin number.
pub fn pin(&self) -> u8 {
self.pin._pin()
}
}
/// Type representing a state machine RX FIFO.
pub struct StateMachineRx<'d, PIO: Instance, const SM: usize> {
pio: PhantomData<&'d mut PIO>,
}
impl<'d, PIO: Instance, const SM: usize> StateMachineRx<'d, PIO, SM> {
/// Check if RX FIFO is empty.
pub fn empty(&self) -> bool {
PIO::PIO.fstat().read().rxempty() & (1u8 << SM) != 0
}
/// Check if RX FIFO is full.
pub fn full(&self) -> bool {
PIO::PIO.fstat().read().rxfull() & (1u8 << SM) != 0
}
/// Check RX FIFO level.
pub fn level(&self) -> u8 {
(PIO::PIO.flevel().read().0 >> (SM * 8 + 4)) as u8 & 0x0f
}
/// Check if state machine has stalled on full RX FIFO.
pub fn stalled(&self) -> bool {
let fdebug = PIO::PIO.fdebug();
let ret = fdebug.read().rxstall() & (1 << SM) != 0;
@ -291,6 +313,7 @@ impl<'d, PIO: Instance, const SM: usize> StateMachineRx<'d, PIO, SM> {
ret
}
/// Check if RX FIFO underflow (i.e. read-on-empty by the system) has occurred.
pub fn underflowed(&self) -> bool {
let fdebug = PIO::PIO.fdebug();
let ret = fdebug.read().rxunder() & (1 << SM) != 0;
@ -300,10 +323,12 @@ impl<'d, PIO: Instance, const SM: usize> StateMachineRx<'d, PIO, SM> {
ret
}
/// Pull data from RX FIFO.
pub fn pull(&mut self) -> u32 {
PIO::PIO.rxf(SM).read()
}
/// Attempt pulling data from RX FIFO.
pub fn try_pull(&mut self) -> Option<u32> {
if self.empty() {
return None;
@ -311,10 +336,12 @@ impl<'d, PIO: Instance, const SM: usize> StateMachineRx<'d, PIO, SM> {
Some(self.pull())
}
/// Wait for RX FIFO readable.
pub fn wait_pull<'a>(&'a mut self) -> FifoInFuture<'a, 'd, PIO, SM> {
FifoInFuture::new(self)
}
/// Prepare DMA transfer from RX FIFO.
pub fn dma_pull<'a, C: Channel, W: Word>(
&'a mut self,
ch: PeripheralRef<'a, C>,
@ -340,22 +367,28 @@ impl<'d, PIO: Instance, const SM: usize> StateMachineRx<'d, PIO, SM> {
}
}
/// Type representing a state machine TX FIFO.
pub struct StateMachineTx<'d, PIO: Instance, const SM: usize> {
pio: PhantomData<&'d mut PIO>,
}
impl<'d, PIO: Instance, const SM: usize> StateMachineTx<'d, PIO, SM> {
/// Check if TX FIFO is empty.
pub fn empty(&self) -> bool {
PIO::PIO.fstat().read().txempty() & (1u8 << SM) != 0
}
/// Check if TX FIFO is full.
pub fn full(&self) -> bool {
PIO::PIO.fstat().read().txfull() & (1u8 << SM) != 0
}
/// Check TX FIFO level.
pub fn level(&self) -> u8 {
(PIO::PIO.flevel().read().0 >> (SM * 8)) as u8 & 0x0f
}
/// Check state machine has stalled on empty TX FIFO.
pub fn stalled(&self) -> bool {
let fdebug = PIO::PIO.fdebug();
let ret = fdebug.read().txstall() & (1 << SM) != 0;
@ -365,6 +398,7 @@ impl<'d, PIO: Instance, const SM: usize> StateMachineTx<'d, PIO, SM> {
ret
}
/// Check if FIFO overflowed.
pub fn overflowed(&self) -> bool {
let fdebug = PIO::PIO.fdebug();
let ret = fdebug.read().txover() & (1 << SM) != 0;
@ -374,10 +408,12 @@ impl<'d, PIO: Instance, const SM: usize> StateMachineTx<'d, PIO, SM> {
ret
}
/// Force push data to TX FIFO.
pub fn push(&mut self, v: u32) {
PIO::PIO.txf(SM).write_value(v);
}
/// Attempt to push data to TX FIFO.
pub fn try_push(&mut self, v: u32) -> bool {
if self.full() {
return false;
@ -386,10 +422,12 @@ impl<'d, PIO: Instance, const SM: usize> StateMachineTx<'d, PIO, SM> {
true
}
/// Wait until FIFO is ready for writing.
pub fn wait_push<'a>(&'a mut self, value: u32) -> FifoOutFuture<'a, 'd, PIO, SM> {
FifoOutFuture::new(self, value)
}
/// Prepare a DMA transfer to TX FIFO.
pub fn dma_push<'a, C: Channel, W: Word>(&'a mut self, ch: PeripheralRef<'a, C>, data: &'a [W]) -> Transfer<'a, C> {
let pio_no = PIO::PIO_NO;
let p = ch.regs();
@ -411,6 +449,7 @@ impl<'d, PIO: Instance, const SM: usize> StateMachineTx<'d, PIO, SM> {
}
}
/// A type representing a single PIO state machine.
pub struct StateMachine<'d, PIO: Instance, const SM: usize> {
rx: StateMachineRx<'d, PIO, SM>,
tx: StateMachineTx<'d, PIO, SM>,
@ -430,52 +469,78 @@ fn assert_consecutive<'d, PIO: Instance>(pins: &[&Pin<'d, PIO>]) {
}
}
/// PIO Execution config.
#[derive(Clone, Copy, Default, Debug)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
#[non_exhaustive]
pub struct ExecConfig {
/// If true, the MSB of the Delay/Side-set instruction field is used as side-set enable, rather than a side-set data bit.
pub side_en: bool,
/// If true, side-set data is asserted to pin directions, instead of pin values.
pub side_pindir: bool,
/// Pin to trigger jump.
pub jmp_pin: u8,
/// After reaching this address, execution is wrapped to wrap_bottom.
pub wrap_top: u8,
/// After reaching wrap_top, execution is wrapped to this address.
pub wrap_bottom: u8,
}
/// PIO shift register config for input or output.
#[derive(Clone, Copy, Default, Debug)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
pub struct ShiftConfig {
/// Number of bits shifted out of OSR before autopull.
pub threshold: u8,
/// Shift direction.
pub direction: ShiftDirection,
/// For output: Pull automatically output shift register is emptied.
/// For input: Push automatically when the input shift register is filled.
pub auto_fill: bool,
}
/// PIO pin config.
#[derive(Clone, Copy, Default, Debug)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
pub struct PinConfig {
/// The number of MSBs of the Delay/Side-set instruction field which are used for side-set.
pub sideset_count: u8,
/// The number of pins asserted by a SET. In the range 0 to 5 inclusive.
pub set_count: u8,
/// The number of pins asserted by an OUT PINS, OUT PINDIRS or MOV PINS instruction. In the range 0 to 32 inclusive.
pub out_count: u8,
/// The pin which is mapped to the least-significant bit of a state machine's IN data bus.
pub in_base: u8,
/// The lowest-numbered pin that will be affected by a side-set operation.
pub sideset_base: u8,
/// The lowest-numbered pin that will be affected by a SET PINS or SET PINDIRS instruction.
pub set_base: u8,
/// The lowest-numbered pin that will be affected by an OUT PINS, OUT PINDIRS or MOV PINS instruction.
pub out_base: u8,
}
/// PIO config.
#[derive(Clone, Copy, Debug)]
pub struct Config<'d, PIO: Instance> {
// CLKDIV
/// Clock divisor register for state machines.
pub clock_divider: FixedU32<U8>,
// EXECCTRL
/// Which data bit to use for inline OUT enable.
pub out_en_sel: u8,
/// Use a bit of OUT data as an auxiliary write enable When used in conjunction with OUT_STICKY.
pub inline_out_en: bool,
/// Continuously assert the most recent OUT/SET to the pins.
pub out_sticky: bool,
/// Which source to use for checking status.
pub status_sel: StatusSource,
/// Status comparison level.
pub status_n: u8,
exec: ExecConfig,
origin: Option<u8>,
// SHIFTCTRL
/// Configure FIFO allocation.
pub fifo_join: FifoJoin,
/// Input shifting config.
pub shift_in: ShiftConfig,
/// Output shifting config.
pub shift_out: ShiftConfig,
// PINCTRL
pins: PinConfig,
@ -505,16 +570,22 @@ impl<'d, PIO: Instance> Default for Config<'d, PIO> {
}
impl<'d, PIO: Instance> Config<'d, PIO> {
/// Get execution configuration.
pub fn get_exec(&self) -> ExecConfig {
self.exec
}
/// Update execution configuration.
pub unsafe fn set_exec(&mut self, e: ExecConfig) {
self.exec = e;
}
/// Get pin configuration.
pub fn get_pins(&self) -> PinConfig {
self.pins
}
/// Update pin configuration.
pub unsafe fn set_pins(&mut self, p: PinConfig) {
self.pins = p;
}
@ -537,6 +608,7 @@ impl<'d, PIO: Instance> Config<'d, PIO> {
self.origin = Some(prog.origin);
}
/// Set pin used to signal jump.
pub fn set_jmp_pin(&mut self, pin: &Pin<'d, PIO>) {
self.exec.jmp_pin = pin.pin();
}
@ -571,6 +643,7 @@ impl<'d, PIO: Instance> Config<'d, PIO> {
}
impl<'d, PIO: Instance + 'd, const SM: usize> StateMachine<'d, PIO, SM> {
/// Set the config for a given PIO state machine.
pub fn set_config(&mut self, config: &Config<'d, PIO>) {
// sm expects 0 for 65536, truncation makes that happen
assert!(config.clock_divider <= 65536, "clkdiv must be <= 65536");
@ -617,7 +690,7 @@ impl<'d, PIO: Instance + 'd, const SM: usize> StateMachine<'d, PIO, SM> {
w.set_out_base(config.pins.out_base);
});
if let Some(origin) = config.origin {
unsafe { pio_instr_util::exec_jmp(self, origin) }
unsafe { instr::exec_jmp(self, origin) }
}
}
@ -626,10 +699,13 @@ impl<'d, PIO: Instance + 'd, const SM: usize> StateMachine<'d, PIO, SM> {
PIO::PIO.sm(SM)
}
/// Restart this state machine.
pub fn restart(&mut self) {
let mask = 1u8 << SM;
PIO::PIO.ctrl().write_set(|w| w.set_sm_restart(mask));
}
/// Enable state machine.
pub fn set_enable(&mut self, enable: bool) {
let mask = 1u8 << SM;
if enable {
@ -639,10 +715,12 @@ impl<'d, PIO: Instance + 'd, const SM: usize> StateMachine<'d, PIO, SM> {
}
}
/// Check if state machine is enabled.
pub fn is_enabled(&self) -> bool {
PIO::PIO.ctrl().read().sm_enable() & (1u8 << SM) != 0
}
/// Restart a state machine's clock divider from an initial phase of 0.
pub fn clkdiv_restart(&mut self) {
let mask = 1u8 << SM;
PIO::PIO.ctrl().write_set(|w| w.set_clkdiv_restart(mask));
@ -690,6 +768,7 @@ impl<'d, PIO: Instance + 'd, const SM: usize> StateMachine<'d, PIO, SM> {
});
}
/// Flush FIFOs for state machine.
pub fn clear_fifos(&mut self) {
// Toggle FJOIN_RX to flush FIFOs
let shiftctrl = Self::this_sm().shiftctrl();
@ -701,21 +780,31 @@ impl<'d, PIO: Instance + 'd, const SM: usize> StateMachine<'d, PIO, SM> {
});
}
/// Instruct state machine to execute a given instructions
///
/// SAFETY: The state machine must be in a state where executing
/// an arbitrary instruction does not crash it.
pub unsafe fn exec_instr(&mut self, instr: u16) {
Self::this_sm().instr().write(|w| w.set_instr(instr));
}
/// Return a read handle for reading state machine outputs.
pub fn rx(&mut self) -> &mut StateMachineRx<'d, PIO, SM> {
&mut self.rx
}
/// Return a handle for writing to inputs.
pub fn tx(&mut self) -> &mut StateMachineTx<'d, PIO, SM> {
&mut self.tx
}
/// Return both read and write handles for the state machine.
pub fn rx_tx(&mut self) -> (&mut StateMachineRx<'d, PIO, SM>, &mut StateMachineTx<'d, PIO, SM>) {
(&mut self.rx, &mut self.tx)
}
}
/// PIO handle.
pub struct Common<'d, PIO: Instance> {
instructions_used: u32,
pio: PhantomData<&'d mut PIO>,
@ -727,18 +816,25 @@ impl<'d, PIO: Instance> Drop for Common<'d, PIO> {
}
}
/// Memory of PIO instance.
pub struct InstanceMemory<'d, PIO: Instance> {
used_mask: u32,
pio: PhantomData<&'d mut PIO>,
}
/// A loaded PIO program.
pub struct LoadedProgram<'d, PIO: Instance> {
/// Memory used by program.
pub used_memory: InstanceMemory<'d, PIO>,
/// Program origin for loading.
pub origin: u8,
/// Wrap controls what to do once program is done executing.
pub wrap: Wrap,
/// Data for 'side' set instruction parameters.
pub side_set: SideSet,
}
/// Errors loading a PIO program.
#[derive(Clone, Copy, PartialEq, Eq, Debug)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
pub enum LoadError {
@ -834,6 +930,7 @@ impl<'d, PIO: Instance> Common<'d, PIO> {
self.instructions_used &= !instrs.used_mask;
}
/// Bypass flipflop synchronizer on GPIO inputs.
pub fn set_input_sync_bypass<'a>(&'a mut self, bypass: u32, mask: u32) {
// this can interfere with per-pin bypass functions. splitting the
// modification is going to be fine since nothing that relies on
@ -842,6 +939,7 @@ impl<'d, PIO: Instance> Common<'d, PIO> {
PIO::PIO.input_sync_bypass().write_clear(|w| *w = mask & !bypass);
}
/// Get bypass configuration.
pub fn get_input_sync_bypass(&self) -> u32 {
PIO::PIO.input_sync_bypass().read()
}
@ -861,6 +959,7 @@ impl<'d, PIO: Instance> Common<'d, PIO> {
}
}
/// Apply changes to all state machines in a batch.
pub fn apply_sm_batch(&mut self, f: impl FnOnce(&mut PioBatch<'d, PIO>)) {
let mut batch = PioBatch {
clkdiv_restart: 0,
@ -878,6 +977,7 @@ impl<'d, PIO: Instance> Common<'d, PIO> {
}
}
/// Represents multiple state machines in a single type.
pub struct PioBatch<'a, PIO: Instance> {
clkdiv_restart: u8,
sm_restart: u8,
@ -887,25 +987,25 @@ pub struct PioBatch<'a, PIO: Instance> {
}
impl<'a, PIO: Instance> PioBatch<'a, PIO> {
pub fn restart_clockdiv<const SM: usize>(&mut self, _sm: &mut StateMachine<'a, PIO, SM>) {
self.clkdiv_restart |= 1 << SM;
}
/// Restart a state machine's clock divider from an initial phase of 0.
pub fn restart<const SM: usize>(&mut self, _sm: &mut StateMachine<'a, PIO, SM>) {
self.clkdiv_restart |= 1 << SM;
}
/// Enable a specific state machine.
pub fn set_enable<const SM: usize>(&mut self, _sm: &mut StateMachine<'a, PIO, SM>, enable: bool) {
self.sm_enable_mask |= 1 << SM;
self.sm_enable |= (enable as u8) << SM;
}
}
/// Type representing a PIO interrupt.
pub struct Irq<'d, PIO: Instance, const N: usize> {
pio: PhantomData<&'d mut PIO>,
}
impl<'d, PIO: Instance, const N: usize> Irq<'d, PIO, N> {
/// Wait for an IRQ to fire.
pub fn wait<'a>(&'a mut self) -> IrqFuture<'a, 'd, PIO> {
IrqFuture {
pio: PhantomData,
@ -914,59 +1014,79 @@ impl<'d, PIO: Instance, const N: usize> Irq<'d, PIO, N> {
}
}
/// Interrupt flags for a PIO instance.
#[derive(Clone)]
pub struct IrqFlags<'d, PIO: Instance> {
pio: PhantomData<&'d mut PIO>,
}
impl<'d, PIO: Instance> IrqFlags<'d, PIO> {
/// Check if interrupt fired.
pub fn check(&self, irq_no: u8) -> bool {
assert!(irq_no < 8);
self.check_any(1 << irq_no)
}
/// Check if any of the interrupts in the bitmap fired.
pub fn check_any(&self, irqs: u8) -> bool {
PIO::PIO.irq().read().irq() & irqs != 0
}
/// Check if all interrupts have fired.
pub fn check_all(&self, irqs: u8) -> bool {
PIO::PIO.irq().read().irq() & irqs == irqs
}
/// Clear interrupt for interrupt number.
pub fn clear(&self, irq_no: usize) {
assert!(irq_no < 8);
self.clear_all(1 << irq_no);
}
/// Clear all interrupts set in the bitmap.
pub fn clear_all(&self, irqs: u8) {
PIO::PIO.irq().write(|w| w.set_irq(irqs))
}
/// Fire a given interrupt.
pub fn set(&self, irq_no: usize) {
assert!(irq_no < 8);
self.set_all(1 << irq_no);
}
/// Fire all interrupts.
pub fn set_all(&self, irqs: u8) {
PIO::PIO.irq_force().write(|w| w.set_irq_force(irqs))
}
}
/// An instance of the PIO driver.
pub struct Pio<'d, PIO: Instance> {
/// PIO handle.
pub common: Common<'d, PIO>,
/// PIO IRQ flags.
pub irq_flags: IrqFlags<'d, PIO>,
/// IRQ0 configuration.
pub irq0: Irq<'d, PIO, 0>,
/// IRQ1 configuration.
pub irq1: Irq<'d, PIO, 1>,
/// IRQ2 configuration.
pub irq2: Irq<'d, PIO, 2>,
/// IRQ3 configuration.
pub irq3: Irq<'d, PIO, 3>,
/// State machine 0 handle.
pub sm0: StateMachine<'d, PIO, 0>,
/// State machine 1 handle.
pub sm1: StateMachine<'d, PIO, 1>,
/// State machine 2 handle.
pub sm2: StateMachine<'d, PIO, 2>,
/// State machine 3 handle.
pub sm3: StateMachine<'d, PIO, 3>,
_pio: PhantomData<&'d mut PIO>,
}
impl<'d, PIO: Instance> Pio<'d, PIO> {
/// Create a new instance of a PIO peripheral.
pub fn new(_pio: impl Peripheral<P = PIO> + 'd, _irq: impl Binding<PIO::Interrupt, InterruptHandler<PIO>>) -> Self {
PIO::state().users.store(5, Ordering::Release);
PIO::state().used_pins.store(0, Ordering::Release);
@ -1003,9 +1123,10 @@ impl<'d, PIO: Instance> Pio<'d, PIO> {
}
}
// we need to keep a record of which pins are assigned to each PIO. make_pio_pin
// notionally takes ownership of the pin it is given, but the wrapped pin cannot
// be treated as an owned resource since dropping it would have to deconfigure
/// Representation of the PIO state keeping a record of which pins are assigned to
/// each PIO.
// make_pio_pin notionally takes ownership of the pin it is given, but the wrapped pin
// cannot be treated as an owned resource since dropping it would have to deconfigure
// the pin, breaking running state machines in the process. pins are also shared
// between all state machines, which makes ownership even messier to track any
// other way.
@ -1059,6 +1180,7 @@ mod sealed {
}
}
/// PIO instance.
pub trait Instance: sealed::Instance + Sized + Unpin {}
macro_rules! impl_pio {
@ -1076,6 +1198,7 @@ macro_rules! impl_pio {
impl_pio!(PIO0, 0, PIO0, PIO0_0, PIO0_IRQ_0);
impl_pio!(PIO1, 1, PIO1, PIO1_0, PIO1_IRQ_0);
/// PIO pin.
pub trait PioPin: sealed::PioPin + gpio::Pin {}
macro_rules! impl_pio_pin {

View file

@ -38,15 +38,18 @@ impl State {
}
}
/// Buffered UART driver.
pub struct BufferedUart<'d, T: Instance> {
pub(crate) rx: BufferedUartRx<'d, T>,
pub(crate) tx: BufferedUartTx<'d, T>,
}
/// Buffered UART RX handle.
pub struct BufferedUartRx<'d, T: Instance> {
pub(crate) phantom: PhantomData<&'d mut T>,
}
/// Buffered UART TX handle.
pub struct BufferedUartTx<'d, T: Instance> {
pub(crate) phantom: PhantomData<&'d mut T>,
}
@ -84,6 +87,7 @@ pub(crate) fn init_buffers<'d, T: Instance + 'd>(
}
impl<'d, T: Instance> BufferedUart<'d, T> {
/// Create a buffered UART instance.
pub fn new(
_uart: impl Peripheral<P = T> + 'd,
irq: impl Binding<T::Interrupt, BufferedInterruptHandler<T>>,
@ -104,6 +108,7 @@ impl<'d, T: Instance> BufferedUart<'d, T> {
}
}
/// Create a buffered UART instance with flow control.
pub fn new_with_rtscts(
_uart: impl Peripheral<P = T> + 'd,
irq: impl Binding<T::Interrupt, BufferedInterruptHandler<T>>,
@ -132,32 +137,39 @@ impl<'d, T: Instance> BufferedUart<'d, T> {
}
}
/// Write to UART TX buffer blocking execution until done.
pub fn blocking_write(&mut self, buffer: &[u8]) -> Result<usize, Error> {
self.tx.blocking_write(buffer)
}
/// Flush UART TX blocking execution until done.
pub fn blocking_flush(&mut self) -> Result<(), Error> {
self.tx.blocking_flush()
}
/// Read from UART RX buffer blocking execution until done.
pub fn blocking_read(&mut self, buffer: &mut [u8]) -> Result<usize, Error> {
self.rx.blocking_read(buffer)
}
/// Check if UART is busy transmitting.
pub fn busy(&self) -> bool {
self.tx.busy()
}
/// Wait until TX is empty and send break condition.
pub async fn send_break(&mut self, bits: u32) {
self.tx.send_break(bits).await
}
/// Split into separate RX and TX handles.
pub fn split(self) -> (BufferedUartRx<'d, T>, BufferedUartTx<'d, T>) {
(self.rx, self.tx)
}
}
impl<'d, T: Instance> BufferedUartRx<'d, T> {
/// Create a new buffered UART RX.
pub fn new(
_uart: impl Peripheral<P = T> + 'd,
irq: impl Binding<T::Interrupt, BufferedInterruptHandler<T>>,
@ -173,6 +185,7 @@ impl<'d, T: Instance> BufferedUartRx<'d, T> {
Self { phantom: PhantomData }
}
/// Create a new buffered UART RX with flow control.
pub fn new_with_rts(
_uart: impl Peripheral<P = T> + 'd,
irq: impl Binding<T::Interrupt, BufferedInterruptHandler<T>>,
@ -253,6 +266,7 @@ impl<'d, T: Instance> BufferedUartRx<'d, T> {
Poll::Ready(result)
}
/// Read from UART RX buffer blocking execution until done.
pub fn blocking_read(&mut self, buf: &mut [u8]) -> Result<usize, Error> {
loop {
match Self::try_read(buf) {
@ -303,6 +317,7 @@ impl<'d, T: Instance> BufferedUartRx<'d, T> {
}
impl<'d, T: Instance> BufferedUartTx<'d, T> {
/// Create a new buffered UART TX.
pub fn new(
_uart: impl Peripheral<P = T> + 'd,
irq: impl Binding<T::Interrupt, BufferedInterruptHandler<T>>,
@ -318,6 +333,7 @@ impl<'d, T: Instance> BufferedUartTx<'d, T> {
Self { phantom: PhantomData }
}
/// Create a new buffered UART TX with flow control.
pub fn new_with_cts(
_uart: impl Peripheral<P = T> + 'd,
irq: impl Binding<T::Interrupt, BufferedInterruptHandler<T>>,
@ -373,6 +389,7 @@ impl<'d, T: Instance> BufferedUartTx<'d, T> {
})
}
/// Write to UART TX buffer blocking execution until done.
pub fn blocking_write(&mut self, buf: &[u8]) -> Result<usize, Error> {
if buf.is_empty() {
return Ok(0);
@ -398,6 +415,7 @@ impl<'d, T: Instance> BufferedUartTx<'d, T> {
}
}
/// Flush UART TX blocking execution until done.
pub fn blocking_flush(&mut self) -> Result<(), Error> {
loop {
let state = T::buffered_state();
@ -407,6 +425,7 @@ impl<'d, T: Instance> BufferedUartTx<'d, T> {
}
}
/// Check if UART is busy.
pub fn busy(&self) -> bool {
T::regs().uartfr().read().busy()
}
@ -466,6 +485,7 @@ impl<'d, T: Instance> Drop for BufferedUartTx<'d, T> {
}
}
/// Interrupt handler.
pub struct BufferedInterruptHandler<T: Instance> {
_uart: PhantomData<T>,
}

View file

@ -938,9 +938,13 @@ macro_rules! impl_instance {
impl_instance!(UART0, UART0_IRQ, 20, 21);
impl_instance!(UART1, UART1_IRQ, 22, 23);
/// Trait for TX pins.
pub trait TxPin<T: Instance>: sealed::TxPin<T> + crate::gpio::Pin {}
/// Trait for RX pins.
pub trait RxPin<T: Instance>: sealed::RxPin<T> + crate::gpio::Pin {}
/// Trait for Clear To Send (CTS) pins.
pub trait CtsPin<T: Instance>: sealed::CtsPin<T> + crate::gpio::Pin {}
/// Trait for Request To Send (RTS) pins.
pub trait RtsPin<T: Instance>: sealed::RtsPin<T> + crate::gpio::Pin {}
macro_rules! impl_pin {

View file

@ -20,7 +20,9 @@ pub(crate) mod sealed {
}
}
/// USB peripheral instance.
pub trait Instance: sealed::Instance + 'static {
/// Interrupt for this peripheral.
type Interrupt: interrupt::typelevel::Interrupt;
}
@ -96,6 +98,7 @@ impl EndpointData {
}
}
/// RP2040 USB driver handle.
pub struct Driver<'d, T: Instance> {
phantom: PhantomData<&'d mut T>,
ep_in: [EndpointData; EP_COUNT],
@ -104,6 +107,7 @@ pub struct Driver<'d, T: Instance> {
}
impl<'d, T: Instance> Driver<'d, T> {
/// Create a new USB driver.
pub fn new(_usb: impl Peripheral<P = T> + 'd, _irq: impl Binding<T::Interrupt, InterruptHandler<T>>) -> Self {
T::Interrupt::unpend();
unsafe { T::Interrupt::enable() };
@ -240,6 +244,7 @@ impl<'d, T: Instance> Driver<'d, T> {
}
}
/// USB interrupt handler.
pub struct InterruptHandler<T: Instance> {
_uart: PhantomData<T>,
}
@ -342,6 +347,7 @@ impl<'d, T: Instance> driver::Driver<'d> for Driver<'d, T> {
}
}
/// Type representing the RP USB bus.
pub struct Bus<'d, T: Instance> {
phantom: PhantomData<&'d mut T>,
ep_out: [EndpointData; EP_COUNT],
@ -461,6 +467,7 @@ trait Dir {
fn waker(i: usize) -> &'static AtomicWaker;
}
/// Type for In direction.
pub enum In {}
impl Dir for In {
fn dir() -> Direction {
@ -473,6 +480,7 @@ impl Dir for In {
}
}
/// Type for Out direction.
pub enum Out {}
impl Dir for Out {
fn dir() -> Direction {
@ -485,6 +493,7 @@ impl Dir for Out {
}
}
/// Endpoint for RP USB driver.
pub struct Endpoint<'d, T: Instance, D> {
_phantom: PhantomData<(&'d mut T, D)>,
info: EndpointInfo,
@ -616,6 +625,7 @@ impl<'d, T: Instance> driver::EndpointIn for Endpoint<'d, T, In> {
}
}
/// Control pipe for RP USB driver.
pub struct ControlPipe<'d, T: Instance> {
_phantom: PhantomData<&'d mut T>,
max_packet_size: u16,