rp: add initial version

This commit is contained in:
Dario Nieuwenhuis 2021-03-29 04:11:32 +02:00
parent 2bcd1aaebb
commit 2cd3bdc90c
23 changed files with 1277 additions and 7 deletions

View File

@ -5,8 +5,8 @@
"rust-analyzer.cargo.allFeatures": false,
"rust-analyzer.checkOnSave.allFeatures": false,
"rust-analyzer.checkOnSave.allTargets": false,
"rust-analyzer.cargo.target": "thumbv7em-none-eabi",
"rust-analyzer.checkOnSave.target": "thumbv7em-none-eabi",
"rust-analyzer.cargo.target": "thumbv6m-none-eabi",
"rust-analyzer.checkOnSave.target": "thumbv6m-none-eabi",
"rust-analyzer.procMacro.enable": true,
"rust-analyzer.cargo.loadOutDirsFromCheck": true,
"files.watcherExclude": {

View File

@ -19,6 +19,8 @@ members = [
exclude = [
"embassy-std",
"embassy-std-examples",
"embassy-rp",
"embassy-rp-examples",
]
[profile.dev]
@ -52,3 +54,5 @@ debug = false
debug-assertions = false
opt-level = 0
overflow-checks = false
[patch.crates-io]

View File

@ -16,3 +16,4 @@ proc-macro = true
[features]
stm32 = []
nrf = []
rp = []

View File

@ -58,5 +58,6 @@ pub fn generate(args: Args) -> TokenStream {
unsafe { embassy::time::set_clock(rtc) };
let alarm = unsafe { make_static(&mut alarm) };
executor.set_alarm(alarm);
)
}

View File

@ -0,0 +1,16 @@
use darling::FromMeta;
use proc_macro2::TokenStream;
use quote::{format_ident, quote};
use syn::spanned::Spanned;
#[derive(Debug, FromMeta)]
pub struct Args {}
pub fn generate(args: Args) -> TokenStream {
quote!(
use embassy_rp::{interrupt, peripherals};
let mut config = embassy_rp::system::Config::default();
unsafe { embassy_rp::system::configure(config) };
)
}

View File

@ -53,5 +53,6 @@ pub fn generate(args: Args) -> TokenStream {
unsafe { embassy::time::set_clock(rtc) };
let alarm = unsafe { make_static(&mut alarm) };
executor.set_alarm(alarm);
)
}

View File

@ -125,7 +125,7 @@ pub fn interrupt_declare(item: TokenStream) -> TokenStream {
type Priority = crate::interrupt::Priority;
fn number(&self) -> u16 {
use cortex_m::interrupt::InterruptNumber;
let irq = crate::pac::interrupt::#name;
let irq = crate::pac::Interrupt::#name;
irq.number() as u16
}
unsafe fn steal() -> Self {
@ -199,7 +199,11 @@ mod chip;
#[path = "chip/stm32.rs"]
mod chip;
#[cfg(any(feature = "nrf", feature = "stm32"))]
#[cfg(feature = "rp")]
#[path = "chip/rp.rs"]
mod chip;
#[cfg(any(feature = "nrf", feature = "stm32", feature = "rp"))]
#[proc_macro_attribute]
pub fn main(args: TokenStream, item: TokenStream) -> TokenStream {
let macro_args = syn::parse_macro_input!(args as syn::AttributeArgs);
@ -267,11 +271,10 @@ pub fn main(args: TokenStream, item: TokenStream) -> TokenStream {
::core::mem::transmute(t)
}
#chip_setup
let mut executor = ::embassy::executor::Executor::new();
let executor = unsafe { make_static(&mut executor) };
executor.set_alarm(alarm);
#chip_setup
executor.run(|spawner| {
spawner.spawn(__embassy_main(spawner)).unwrap();

View File

@ -0,0 +1,30 @@
[unstable]
build-std = ["core"]
build-std-features = ["panic_immediate_abort"]
[target.'cfg(all(target_arch = "arm", target_os = "none"))']
runner = "probe-run-rp --chip RP2040"
rustflags = [
# LLD (shipped with the Rust toolchain) is used as the default linker
"-C", "link-arg=--nmagic",
"-C", "link-arg=-Tlink.x",
"-C", "link-arg=-Tdefmt.x",
# if you run into problems with LLD switch to the GNU linker by commenting out
# this line
# "-C", "linker=arm-none-eabi-ld",
# if you need to link to pre-compiled C libraries provided by a C toolchain
# use GCC as the linker by commenting out both lines above and then
# uncommenting the three lines below
# "-C", "linker=arm-none-eabi-gcc",
# "-C", "link-arg=-Wl,-Tlink.x",
# "-C", "link-arg=-nostartfiles",
# Code-size optimizations.
"-Z", "trap-unreachable=no",
]
[build]
target = "thumbv6m-none-eabi" # Cortex-M0 and Cortex-M0+

View File

@ -0,0 +1,33 @@
[package]
authors = ["Dario Nieuwenhuis <dirbaio@dirbaio.net>"]
edition = "2018"
name = "embassy-rp-examples"
version = "0.1.0"
[features]
default = [
"defmt-default",
]
defmt-default = []
defmt-trace = []
defmt-debug = []
defmt-info = []
defmt-warn = []
defmt-error = []
[dependencies]
embassy = { version = "0.1.0", path = "../embassy", features = ["defmt", "defmt-trace"] }
embassy-rp = { version = "0.1.0", path = "../embassy-rp", features = ["defmt", "defmt-trace"] }
rp2040-boot2 = { git = "https://github.com/rp-rs/rp2040-boot2-rs", branch="main" }
rp2040-pac2 = { git = "https://github.com/Dirbaio/rp2040-pac", rev="254f4677937801155ca3cb17c7bb9d38eb62683e" }
atomic-polyfill = { version = "0.1.1" }
defmt = "0.2.0"
defmt-rtt = "0.2.0"
cortex-m = { version = "0.7.1", features = ["inline-asm"] }
cortex-m-rt = "0.6.13"
embedded-hal = { version = "0.2.4" }
panic-probe = "0.1.0"
futures = { version = "0.3.8", default-features = false, features = ["async-await", "cfg-target-has-atomic", "unstable"] }

View File

@ -0,0 +1,31 @@
//! This build script copies the `memory.x` file from the crate root into
//! a directory where the linker can always find it at build time.
//! For many projects this is optional, as the linker always searches the
//! project root directory -- wherever `Cargo.toml` is. However, if you
//! are using a workspace or have a more complicated build setup, this
//! build script becomes required. Additionally, by requesting that
//! Cargo re-run the build script whenever `memory.x` is changed,
//! updating `memory.x` ensures a rebuild of the application with the
//! new memory settings.
use std::env;
use std::fs::File;
use std::io::Write;
use std::path::PathBuf;
fn main() {
// Put `memory.x` in our output directory and ensure it's
// on the linker search path.
let out = &PathBuf::from(env::var_os("OUT_DIR").unwrap());
File::create(out.join("memory.x"))
.unwrap()
.write_all(include_bytes!("memory.x"))
.unwrap();
println!("cargo:rustc-link-search={}", out.display());
// By default, Cargo will re-run a build script whenever
// any file in the project changes. By specifying `memory.x`
// here, we ensure the build script is only re-run when
// `memory.x` is changed.
println!("cargo:rerun-if-changed=memory.x");
}

View File

@ -0,0 +1,13 @@
MEMORY {
BOOT2 : ORIGIN = 0x10000000, LENGTH = 0x100
FLASH : ORIGIN = 0x10000100, LENGTH = 2048K - 0x100
RAM : ORIGIN = 0x20000000, LENGTH = 256K
}
SECTIONS {
/* ### Boot loader */
.boot2 ORIGIN(BOOT2) :
{
KEEP(*(.boot2));
} > BOOT2
} INSERT BEFORE .text;

View File

@ -0,0 +1,72 @@
#![no_std]
#![no_main]
#![feature(asm)]
#![feature(min_type_alias_impl_trait)]
#![feature(impl_trait_in_bindings)]
#![feature(type_alias_impl_trait)]
use core::sync::atomic::{AtomicUsize, Ordering};
use defmt::{panic, *};
use defmt_rtt as _;
use embassy::executor::Spawner;
use embassy::interrupt::InterruptExt;
use embassy_rp::{dma, gpio, interrupt, uart, Peripherals};
use embedded_hal::digital::v2::OutputPin;
use panic_probe as _;
use rp2040_pac2 as pac;
#[link_section = ".boot2"]
#[used]
pub static BOOT2: [u8; 256] = rp2040_boot2::BOOT_LOADER;
defmt::timestamp! {"{=u64}", {
static COUNT: AtomicUsize = AtomicUsize::new(0);
// NOTE(no-CAS) `timestamps` runs with interrupts disabled
let n = COUNT.load(Ordering::Relaxed);
COUNT.store(n + 1, Ordering::Relaxed);
n as u64
}
}
#[embassy::main]
async fn main(spanwer: Spawner) {
let p = unwrap!(Peripherals::take());
let mut config = uart::Config::default();
let mut uart = uart::Uart::new(p.UART0, p.PIN_0, p.PIN_1, p.PIN_2, p.PIN_3, config);
uart.send("Hello World!\r\n".as_bytes());
let mut led = gpio::Output::new(p.PIN_25, gpio::Level::Low);
let irq = interrupt::take!(DMA_IRQ_0);
unsafe {
//pac::DMA.inte0().write(|w| w.set_inte0(1 << 0));
}
irq.set_handler(dma_irq);
irq.unpend();
irq.enable();
let from: [u32; 4] = [1, 2, 3, 4];
let mut to: [u32; 4] = [9, 8, 7, 6];
info!("before dma: from = {:?}, to = {:?}", from, to);
cortex_m::asm::delay(4_000_000);
dma::Dma::copy(p.DMA_CH0, &from, &mut to);
cortex_m::asm::delay(4_000_000);
info!("after dma: from = {:?}, to = {:?}", from, to);
loop {
info!("led on!");
uart.send("ON!\r".as_bytes());
led.set_high().unwrap();
cortex_m::asm::delay(1_000_000);
info!("led off!");
uart.send("Off!\r".as_bytes());
led.set_low().unwrap();
cortex_m::asm::delay(4_000_000);
}
}
unsafe fn dma_irq(ctx: *mut ()) {
info!("DMA IRQ!");
}

25
embassy-rp/Cargo.toml Normal file
View File

@ -0,0 +1,25 @@
[package]
name = "embassy-rp"
version = "0.1.0"
authors = ["Dario Nieuwenhuis <dirbaio@dirbaio.net>"]
edition = "2018"
[features]
defmt-trace = [ ]
defmt-debug = [ ]
defmt-info = [ ]
defmt-warn = [ ]
defmt-error = [ ]
[dependencies]
embassy = { version = "0.1.0", path = "../embassy" }
embassy-extras = {version = "0.1.0", path = "../embassy-extras" }
embassy-macros = { version = "0.1.0", path = "../embassy-macros", features = ["rp"]}
defmt = { version = "0.2.0", optional = true }
log = { version = "0.4.11", optional = true }
cortex-m-rt = "0.6.13"
cortex-m = "0.7.1"
rp2040-pac2 = { git = "https://github.com/Dirbaio/rp2040-pac", rev="254f4677937801155ca3cb17c7bb9d38eb62683e", features = ["rt"] }
embedded-hal = { version = "0.2.4", features = [ "unproven" ] }

30
embassy-rp/funcsel.txt Normal file
View File

@ -0,0 +1,30 @@
0 SPI0 RX UART0 TX I2C0 SDA PWM0 A SIO PIO0 PIO1 USB OVCUR DET
1 SPI0 CSn UART0 RX I2C0 SCL PWM0 B SIO PIO0 PIO1 USB VBUS DET
2 SPI0 SCK UART0 CTS I2C1 SDA PWM1 A SIO PIO0 PIO1 USB VBUS EN
3 SPI0 TX UART0 RTS I2C1 SCL PWM1 B SIO PIO0 PIO1 USB OVCUR DET
4 SPI0 RX UART1 TX I2C0 SDA PWM2 A SIO PIO0 PIO1 USB VBUS DET
5 SPI0 CSn UART1 RX I2C0 SCL PWM2 B SIO PIO0 PIO1 USB VBUS EN
6 SPI0 SCK UART1 CTS I2C1 SDA PWM3 A SIO PIO0 PIO1 USB OVCUR DET
7 SPI0 TX UART1 RTS I2C1 SCL PWM3 B SIO PIO0 PIO1 USB VBUS DET
8 SPI1 RX UART1 TX I2C0 SDA PWM4 A SIO PIO0 PIO1 USB VBUS EN
9 SPI1 CSn UART1 RX I2C0 SCL PWM4 B SIO PIO0 PIO1 USB OVCUR DET
10 SPI1 SCK UART1 CTS I2C1 SDA PWM5 A SIO PIO0 PIO1 USB VBUS DET
11 SPI1 TX UART1 RTS I2C1 SCL PWM5 B SIO PIO0 PIO1 USB VBUS EN
12 SPI1 RX UART0 TX I2C0 SDA PWM6 A SIO PIO0 PIO1 USB OVCUR DET
13 SPI1 CSn UART0 RX I2C0 SCL PWM6 B SIO PIO0 PIO1 USB VBUS DET
14 SPI1 SCK UART0 CTS I2C1 SDA PWM7 A SIO PIO0 PIO1 USB VBUS EN
15 SPI1 TX UART0 RTS I2C1 SCL PWM7 B SIO PIO0 PIO1 USB OVCUR DET
16 SPI0 RX UART0 TX I2C0 SDA PWM0 A SIO PIO0 PIO1 USB VBUS DET
17 SPI0 CSn UART0 RX I2C0 SCL PWM0 B SIO PIO0 PIO1 USB VBUS EN
18 SPI0 SCK UART0 CTS I2C1 SDA PWM1 A SIO PIO0 PIO1 USB OVCUR DET
19 SPI0 TX UART0 RTS I2C1 SCL PWM1 B SIO PIO0 PIO1 USB VBUS DET
20 SPI0 RX UART1 TX I2C0 SDA PWM2 A SIO PIO0 PIO1 CLOCK GPIN0 USB VBUS EN
21 SPI0 CSn UART1 RX I2C0 SCL PWM2 B SIO PIO0 PIO1 CLOCK GPOUT0 USB OVCUR DET
22 SPI0 SCK UART1 CTS I2C1 SDA PWM3 A SIO PIO0 PIO1 CLOCK GPIN1 USB VBUS DET
23 SPI0 TX UART1 RTS I2C1 SCL PWM3 B SIO PIO0 PIO1 CLOCK GPOUT1 USB VBUS EN
24 SPI1 RX UART1 TX I2C0 SDA PWM4 A SIO PIO0 PIO1 CLOCK GPOUT2 USB OVCUR DET
25 SPI1 CSn UART1 RX I2C0 SCL PWM4 B SIO PIO0 PIO1 CLOCK GPOUT3 USB VBUS DET
26 SPI1 SCK UART1 CTS I2C1 SDA PWM5 A SIO PIO0 PIO1 USB VBUS EN
27 SPI1 TX UART1 RTS I2C1 SCL PWM5 B SIO PIO0 PIO1 USB OVCUR DET
28 SPI1 RX UART0 TX I2C0 SDA PWM6 A SIO PIO0 PIO1 USB VBUS DET
29 SPI1 CSn UART0 RX I2C0 SCL PWM6 B SIO PIO0 PIO1 USB VBUS EN

87
embassy-rp/src/dma.rs Normal file
View File

@ -0,0 +1,87 @@
use core::sync::atomic::{compiler_fence, Ordering};
use defmt::{assert, *};
use crate::{pac, peripherals};
use pac::dma::vals;
pub struct Dma<T: Channel> {
inner: T,
}
impl<T: Channel> Dma<T> {
pub fn copy(inner: T, from: &[u32], to: &mut [u32]) {
assert!(from.len() == to.len());
unsafe {
let p = inner.regs();
p.read_addr().write_value(from.as_ptr() as u32);
p.write_addr().write_value(to.as_mut_ptr() as u32);
p.trans_count().write_value(from.len() as u32);
compiler_fence(Ordering::SeqCst);
p.ctrl_trig().write(|w| {
w.set_data_size(vals::DataSize::SIZE_WORD);
w.set_incr_read(true);
w.set_incr_write(true);
w.set_chain_to(inner.number());
w.set_en(true);
});
while p.ctrl_trig().read().busy() {}
compiler_fence(Ordering::SeqCst);
}
}
}
mod sealed {
use super::*;
pub trait Channel {
fn number(&self) -> u8;
fn regs(&self) -> pac::dma::Channel {
pac::DMA.ch(self.number() as _)
}
}
}
pub trait Channel: sealed::Channel {}
pub struct AnyChannel {
number: u8,
}
impl Channel for AnyChannel {}
impl sealed::Channel for AnyChannel {
fn number(&self) -> u8 {
self.number
}
}
macro_rules! channel {
($type:ident, $num:expr) => {
impl Channel for peripherals::$type {}
impl sealed::Channel for peripherals::$type {
fn number(&self) -> u8 {
$num
}
}
};
}
channel!(DMA_CH0, 0);
channel!(DMA_CH1, 1);
channel!(DMA_CH2, 2);
channel!(DMA_CH3, 3);
channel!(DMA_CH4, 4);
channel!(DMA_CH5, 5);
channel!(DMA_CH6, 6);
channel!(DMA_CH7, 7);
channel!(DMA_CH8, 8);
channel!(DMA_CH9, 9);
channel!(DMA_CH10, 10);
channel!(DMA_CH11, 11);

118
embassy-rp/src/fmt.rs Normal file
View File

@ -0,0 +1,118 @@
#![macro_use]
#[cfg(all(feature = "defmt", feature = "log"))]
compile_error!("You may not enable both `defmt` and `log` features.");
pub use fmt::*;
#[cfg(feature = "defmt")]
mod fmt {
pub use defmt::{
assert, assert_eq, assert_ne, debug, debug_assert, debug_assert_eq, debug_assert_ne, error,
info, panic, todo, trace, unreachable, unwrap, warn,
};
}
#[cfg(feature = "log")]
mod fmt {
pub use core::{
assert, assert_eq, assert_ne, debug_assert, debug_assert_eq, debug_assert_ne, panic, todo,
unreachable,
};
pub use log::{debug, error, info, trace, warn};
}
#[cfg(not(any(feature = "defmt", feature = "log")))]
mod fmt {
#![macro_use]
pub use core::{
assert, assert_eq, assert_ne, debug_assert, debug_assert_eq, debug_assert_ne, panic, todo,
unreachable,
};
#[macro_export]
macro_rules! trace {
($($msg:expr),+ $(,)?) => {
()
};
}
#[macro_export]
macro_rules! debug {
($($msg:expr),+ $(,)?) => {
()
};
}
#[macro_export]
macro_rules! info {
($($msg:expr),+ $(,)?) => {
()
};
}
#[macro_export]
macro_rules! warn {
($($msg:expr),+ $(,)?) => {
()
};
}
#[macro_export]
macro_rules! error {
($($msg:expr),+ $(,)?) => {
()
};
}
}
#[cfg(not(feature = "defmt"))]
#[macro_export]
macro_rules! unwrap {
($arg:expr) => {
match $crate::fmt::Try::into_result($arg) {
::core::result::Result::Ok(t) => t,
::core::result::Result::Err(e) => {
::core::panic!("unwrap of `{}` failed: {:?}", ::core::stringify!($arg), e);
}
}
};
($arg:expr, $($msg:expr),+ $(,)? ) => {
match $crate::fmt::Try::into_result($arg) {
::core::result::Result::Ok(t) => t,
::core::result::Result::Err(e) => {
::core::panic!("unwrap of `{}` failed: {}: {:?}", ::core::stringify!($arg), ::core::format_args!($($msg,)*), e);
}
}
}
}
#[derive(Debug, Copy, Clone, Eq, PartialEq)]
pub struct NoneError;
pub trait Try {
type Ok;
type Error;
fn into_result(self) -> Result<Self::Ok, Self::Error>;
}
impl<T> Try for Option<T> {
type Ok = T;
type Error = NoneError;
#[inline]
fn into_result(self) -> Result<T, NoneError> {
self.ok_or(NoneError)
}
}
impl<T, E> Try for Result<T, E> {
type Ok = T;
type Error = E;
#[inline]
fn into_result(self) -> Self {
self
}
}

250
embassy-rp/src/gpio.rs Normal file
View File

@ -0,0 +1,250 @@
use core::marker::PhantomData;
use crate::pac;
use crate::pac::generic::{Reg, RW};
use crate::pac::SIO;
use crate::peripherals;
use embassy::util::PeripheralBorrow;
use embassy_extras::{impl_unborrow, unborrow};
use embedded_hal::digital::v2::{InputPin, OutputPin, StatefulOutputPin};
/// Represents a digital input or output level.
#[derive(Debug, Eq, PartialEq)]
pub enum Level {
Low,
High,
}
/// Represents a pull setting for an input.
#[derive(Debug, Eq, PartialEq)]
pub enum Pull {
None,
Up,
Down,
}
/// A GPIO bank with up to 32 pins.
#[derive(Debug, Eq, PartialEq)]
pub enum Bank {
Bank0 = 0,
Qspi = 1,
}
pub struct Input<'d, T: Pin> {
pin: T,
phantom: PhantomData<&'d mut T>,
}
impl<'d, T: Pin> Input<'d, T> {
pub fn new(pin: impl PeripheralBorrow<Target = T> + 'd, pull: Pull) -> Self {
unborrow!(pin);
// todo
Self {
pin,
phantom: PhantomData,
}
}
}
impl<'d, T: Pin> Drop for Input<'d, T> {
fn drop(&mut self) {
// todo
}
}
impl<'d, T: Pin> InputPin for Input<'d, T> {
type Error = !;
fn is_high(&self) -> Result<bool, Self::Error> {
self.is_low().map(|v| !v)
}
fn is_low(&self) -> Result<bool, Self::Error> {
// todo
Ok(true)
}
}
pub struct Output<'d, T: Pin> {
pin: T,
phantom: PhantomData<&'d mut T>,
}
impl<'d, T: Pin> Output<'d, T> {
// TODO opendrain
pub fn new(pin: impl PeripheralBorrow<Target = T> + 'd, initial_output: Level) -> Self {
unborrow!(pin);
unsafe {
match initial_output {
Level::High => pin.sio_out().value_set().write_value(1 << pin.pin()),
Level::Low => pin.sio_out().value_clr().write_value(1 << pin.pin()),
}
pin.sio_oe().value_set().write_value(1 << pin.pin());
pin.io().ctrl().write(|w| {
w.set_funcsel(pac::io::vals::Gpio0CtrlFuncsel::SIO_0.0);
});
}
Self {
pin,
phantom: PhantomData,
}
}
}
impl<'d, T: Pin> Drop for Output<'d, T> {
fn drop(&mut self) {
// todo
}
}
impl<'d, T: Pin> OutputPin for Output<'d, T> {
type Error = !;
/// Set the output as high.
fn set_high(&mut self) -> Result<(), Self::Error> {
let val = 1 << self.pin.pin();
unsafe { self.pin.sio_out().value_set().write_value(val) };
Ok(())
}
/// Set the output as low.
fn set_low(&mut self) -> Result<(), Self::Error> {
let val = 1 << self.pin.pin();
unsafe { self.pin.sio_out().value_clr().write_value(val) };
Ok(())
}
}
impl<'d, T: Pin> StatefulOutputPin for Output<'d, T> {
/// Is the output pin set as high?
fn is_set_high(&self) -> Result<bool, Self::Error> {
self.is_set_low().map(|v| !v)
}
/// Is the output pin set as low?
fn is_set_low(&self) -> Result<bool, Self::Error> {
// todo
Ok(true)
}
}
pub(crate) mod sealed {
use super::*;
pub trait Pin: Sized {
fn pin_bank(&self) -> u8;
#[inline]
fn pin(&self) -> u8 {
self.pin_bank() & 0x1f
}
#[inline]
fn bank(&self) -> Bank {
if self.pin_bank() & 0x20 == 0 {
Bank::Bank0
} else {
Bank::Qspi
}
}
fn io(&self) -> pac::io::Gpio {
let block = match self.bank() {
Bank::Bank0 => crate::pac::IO_BANK0,
Bank::Qspi => crate::pac::IO_QSPI,
};
block.gpio(self.pin() as _)
}
fn pad_ctrl(&self) -> Reg<pac::pads::regs::GpioCtrl, RW> {
let block = match self.bank() {
Bank::Bank0 => crate::pac::PADS_BANK0,
Bank::Qspi => crate::pac::PADS_QSPI,
};
block.gpio(self.pin() as _)
}
fn sio_out(&self) -> pac::sio::Gpio {
SIO.gpio_out(self.bank() as _)
}
fn sio_oe(&self) -> pac::sio::Gpio {
SIO.gpio_oe(self.bank() as _)
}
fn sio_in(&self) -> Reg<u32, RW> {
SIO.gpio_in(self.bank() as _)
}
}
}
pub trait Pin: sealed::Pin {
/// Degrade to a generic pin struct
fn degrade(self) -> AnyPin {
AnyPin {
pin_bank: self.pin_bank(),
}
}
}
pub struct AnyPin {
pin_bank: u8,
}
impl_unborrow!(AnyPin);
impl Pin for AnyPin {}
impl sealed::Pin for AnyPin {
fn pin_bank(&self) -> u8 {
self.pin_bank
}
}
macro_rules! impl_pin {
($name:ident, $bank:expr, $pin_num:expr) => {
impl Pin for peripherals::$name {}
impl sealed::Pin for peripherals::$name {
fn pin_bank(&self) -> u8 {
($bank as u8) * 32 + $pin_num
}
}
};
}
impl_pin!(PIN_0, Bank::Bank0, 0);
impl_pin!(PIN_1, Bank::Bank0, 1);
impl_pin!(PIN_2, Bank::Bank0, 2);
impl_pin!(PIN_3, Bank::Bank0, 3);
impl_pin!(PIN_4, Bank::Bank0, 4);
impl_pin!(PIN_5, Bank::Bank0, 5);
impl_pin!(PIN_6, Bank::Bank0, 6);
impl_pin!(PIN_7, Bank::Bank0, 7);
impl_pin!(PIN_8, Bank::Bank0, 8);
impl_pin!(PIN_9, Bank::Bank0, 9);
impl_pin!(PIN_10, Bank::Bank0, 10);
impl_pin!(PIN_11, Bank::Bank0, 11);
impl_pin!(PIN_12, Bank::Bank0, 12);
impl_pin!(PIN_13, Bank::Bank0, 13);
impl_pin!(PIN_14, Bank::Bank0, 14);
impl_pin!(PIN_15, Bank::Bank0, 15);
impl_pin!(PIN_16, Bank::Bank0, 16);
impl_pin!(PIN_17, Bank::Bank0, 17);
impl_pin!(PIN_18, Bank::Bank0, 18);
impl_pin!(PIN_19, Bank::Bank0, 19);
impl_pin!(PIN_20, Bank::Bank0, 20);
impl_pin!(PIN_21, Bank::Bank0, 21);
impl_pin!(PIN_22, Bank::Bank0, 22);
impl_pin!(PIN_23, Bank::Bank0, 23);
impl_pin!(PIN_24, Bank::Bank0, 24);
impl_pin!(PIN_25, Bank::Bank0, 25);
impl_pin!(PIN_26, Bank::Bank0, 26);
impl_pin!(PIN_27, Bank::Bank0, 27);
impl_pin!(PIN_28, Bank::Bank0, 28);
impl_pin!(PIN_29, Bank::Bank0, 29);
impl_pin!(PIN_QSPI_SCLK, Bank::Qspi, 0);
impl_pin!(PIN_QSPI_SS, Bank::Qspi, 1);
impl_pin!(PIN_QSPI_SD0, Bank::Qspi, 2);
impl_pin!(PIN_QSPI_SD1, Bank::Qspi, 3);
impl_pin!(PIN_QSPI_SD2, Bank::Qspi, 4);
impl_pin!(PIN_QSPI_SD3, Bank::Qspi, 5);

110
embassy-rp/src/interrupt.rs Normal file
View File

@ -0,0 +1,110 @@
//! Interrupt management
//!
//! This module implements an API for managing interrupts compatible with
//! nrf_softdevice::interrupt. Intended for switching between the two at compile-time.
use core::sync::atomic::{compiler_fence, Ordering};
use crate::pac::NVIC_PRIO_BITS;
// Re-exports
pub use cortex_m::interrupt::{CriticalSection, Mutex};
pub use embassy::interrupt::{declare, take, Interrupt};
#[derive(Debug, Copy, Clone, Eq, PartialEq, Ord, PartialOrd)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
#[repr(u8)]
pub enum Priority {
Level0 = 0,
Level1 = 1,
Level2 = 2,
Level3 = 3,
Level4 = 4,
Level5 = 5,
Level6 = 6,
Level7 = 7,
}
impl From<u8> for Priority {
fn from(priority: u8) -> Self {
match priority >> (8 - NVIC_PRIO_BITS) {
0 => Self::Level0,
1 => Self::Level1,
2 => Self::Level2,
3 => Self::Level3,
4 => Self::Level4,
5 => Self::Level5,
6 => Self::Level6,
7 => Self::Level7,
_ => unreachable!(),
}
}
}
impl From<Priority> for u8 {
fn from(p: Priority) -> Self {
(p as u8) << (8 - NVIC_PRIO_BITS)
}
}
#[inline]
pub fn free<F, R>(f: F) -> R
where
F: FnOnce(&CriticalSection) -> R,
{
unsafe {
// TODO: assert that we're in privileged level
// Needed because disabling irqs in non-privileged level is a noop, which would break safety.
let primask: u32;
asm!("mrs {}, PRIMASK", out(reg) primask);
asm!("cpsid i");
// Prevent compiler from reordering operations inside/outside the critical section.
compiler_fence(Ordering::SeqCst);
let r = f(&CriticalSection::new());
compiler_fence(Ordering::SeqCst);
if primask & 1 == 0 {
asm!("cpsie i");
}
r
}
}
mod irqs {
use super::*;
declare!(TIMER_IRQ_0);
declare!(TIMER_IRQ_1);
declare!(TIMER_IRQ_2);
declare!(TIMER_IRQ_3);
declare!(PWM_IRQ_WRAP);
declare!(USBCTRL_IRQ);
declare!(XIP_IRQ);
declare!(PIO0_IRQ_0);
declare!(PIO0_IRQ_1);
declare!(PIO1_IRQ_0);
declare!(PIO1_IRQ_1);
declare!(DMA_IRQ_0);
declare!(DMA_IRQ_1);
declare!(IO_IRQ_BANK0);
declare!(IO_IRQ_QSPI);
declare!(SIO_IRQ_PROC0);
declare!(SIO_IRQ_PROC1);
declare!(CLOCKS_IRQ);
declare!(SPI0_IRQ);
declare!(SPI1_IRQ);
declare!(UART0_IRQ);
declare!(UART1_IRQ);
declare!(ADC_IRQ_FIFO);
declare!(I2C0_IRQ);
declare!(I2C1_IRQ);
declare!(RTC_IRQ);
}
pub use irqs::*;

74
embassy-rp/src/lib.rs Normal file
View File

@ -0,0 +1,74 @@
#![no_std]
#![feature(generic_associated_types)]
#![feature(asm)]
#![feature(type_alias_impl_trait)]
#![feature(never_type)]
pub use rp2040_pac2 as pac;
// This mod MUST go first, so that the others see its macros.
pub(crate) mod fmt;
pub mod interrupt;
pub mod dma;
pub mod gpio;
pub mod pll;
pub mod resets;
pub mod system;
pub mod uart;
embassy_extras::peripherals! {
PIN_0,
PIN_1,
PIN_2,
PIN_3,
PIN_4,
PIN_5,
PIN_6,
PIN_7,
PIN_8,
PIN_9,
PIN_10,
PIN_11,
PIN_12,
PIN_13,
PIN_14,
PIN_15,
PIN_16,
PIN_17,
PIN_18,
PIN_19,
PIN_20,
PIN_21,
PIN_22,
PIN_23,
PIN_24,
PIN_25,
PIN_26,
PIN_27,
PIN_28,
PIN_29,
PIN_QSPI_SCLK,
PIN_QSPI_SS,
PIN_QSPI_SD0,
PIN_QSPI_SD1,
PIN_QSPI_SD2,
PIN_QSPI_SD3,
UART0,
UART1,
DMA_CH0,
DMA_CH1,
DMA_CH2,
DMA_CH3,
DMA_CH4,
DMA_CH5,
DMA_CH6,
DMA_CH7,
DMA_CH8,
DMA_CH9,
DMA_CH10,
DMA_CH11,
}

79
embassy-rp/src/pll.rs Normal file
View File

@ -0,0 +1,79 @@
use core::ops::Deref;
use defmt::{assert, *};
use crate::pac;
const XOSC_MHZ: u32 = 12;
pub struct PLL<T: Instance> {
inner: T,
}
impl<T: Instance> PLL<T> {
pub fn new(inner: T) -> Self {
Self { inner }
}
pub fn configure(&mut self, refdiv: u32, vco_freq: u32, post_div1: u8, post_div2: u8) {
unsafe {
let p = self.inner.regs();
// Power off in case it's already running
p.pwr().write(|w| {
w.set_vcopd(true);
w.set_postdivpd(true);
w.set_dsmpd(true);
w.set_pd(true);
});
p.fbdiv_int().write(|w| w.set_fbdiv_int(0));
let ref_mhz = XOSC_MHZ / refdiv;
p.cs().write(|w| w.set_refdiv(ref_mhz as _));
let fbdiv = vco_freq / (ref_mhz * 1_000_000);
assert!(fbdiv >= 16 && fbdiv <= 520);
assert!((post_div1 >= 1 && post_div1 <= 7) && (post_div2 >= 1 && post_div2 <= 7));
assert!(post_div2 <= post_div1);
assert!(ref_mhz <= (vco_freq / 16));
p.fbdiv_int().write(|w| w.set_fbdiv_int(fbdiv as _));
p.pwr().modify(|w| {
w.set_pd(false);
w.set_vcopd(false);
});
while !p.cs().read().lock() {}
p.prim().write(|w| {
w.set_postdiv1(post_div1);
w.set_postdiv2(post_div2);
});
p.pwr().modify(|w| w.set_postdivpd(false));
}
}
}
mod sealed {
pub trait Instance {}
impl Instance for super::PllSys {}
impl Instance for super::PllUsb {}
}
// todo make owned
pub struct PllSys;
pub struct PllUsb;
pub trait Instance {
fn regs(&self) -> pac::pll::Pll;
}
impl Instance for PllSys {
fn regs(&self) -> pac::pll::Pll {
pac::PLL_SYS
}
}
impl Instance for PllUsb {
fn regs(&self) -> pac::pll::Pll {
pac::PLL_USB
}
}

29
embassy-rp/src/resets.rs Normal file
View File

@ -0,0 +1,29 @@
use crate::pac;
pub use pac::resets::regs::Peripherals;
pub const ALL_PERIPHERALS: Peripherals = Peripherals(0x01ffffff);
pub struct Resets {}
impl Resets {
pub fn new() -> Self {
Self {}
}
pub fn reset(&self, peris: Peripherals) {
unsafe {
pac::RESETS.reset().write_value(peris);
}
}
pub fn unreset_wait(&self, peris: Peripherals) {
unsafe {
// TODO use the "atomic clear" register version
pac::RESETS
.reset()
.modify(|v| *v = Peripherals(v.0 & !peris.0));
while ((!pac::RESETS.reset_done().read().0) & peris.0) != 0 {}
}
}
}

90
embassy-rp/src/system.rs Normal file
View File

@ -0,0 +1,90 @@
use crate::{pac, pll, resets};
#[non_exhaustive]
pub struct Config {}
impl Default for Config {
fn default() -> Self {
Self {}
}
}
/// safety: must only call once.
pub unsafe fn configure(_config: Config) {
// Now reset all the peripherals, except QSPI and XIP (we're using those
// to execute from external flash!)
let resets = resets::Resets::new();
// Reset everything except:
// - QSPI (we're using it to run this code!)
// - PLLs (it may be suicide if that's what's clocking us)
let mut peris = resets::ALL_PERIPHERALS;
peris.set_io_qspi(false);
peris.set_pads_qspi(false);
peris.set_pll_sys(false);
peris.set_pll_usb(false);
resets.reset(peris);
let mut peris = resets::ALL_PERIPHERALS;
peris.set_adc(false);
peris.set_rtc(false);
peris.set_spi0(false);
peris.set_spi1(false);
peris.set_uart0(false);
peris.set_uart1(false);
peris.set_usbctrl(false);
resets.unreset_wait(peris);
// xosc 12 mhz
pac::WATCHDOG.tick().write(|w| {
w.set_cycles(XOSC_MHZ as u16);
w.set_enable(true);
});
pac::CLOCKS
.clk_sys_resus_ctrl()
.write_value(pac::clocks::regs::ClkSysResusCtrl(0));
// Enable XOSC
// TODO extract to HAL module
const XOSC_MHZ: u32 = 12;
pac::XOSC
.ctrl()
.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.ctrl().write(|w| {
w.set_freq_range(pac::xosc::vals::CtrlFreqRange::_1_15MHZ);
w.set_enable(pac::xosc::vals::CtrlEnable::ENABLE);
});
while !pac::XOSC.status().read().stable() {}
// Before we touch PLLs, switch sys and ref cleanly away from their aux sources.
pac::CLOCKS
.clk_sys_ctrl()
.modify(|w| w.set_src(pac::clocks::vals::ClkSysCtrlSrc::CLK_REF));
while pac::CLOCKS.clk_sys_selected().read() != 1 {}
pac::CLOCKS
.clk_ref_ctrl()
.modify(|w| w.set_src(pac::clocks::vals::ClkRefCtrlSrc::ROSC_CLKSRC_PH));
while pac::CLOCKS.clk_ref_selected().read() != 1 {}
let mut peris = resets::Peripherals(0);
peris.set_pll_sys(true);
peris.set_pll_usb(true);
resets.reset(peris);
resets.unreset_wait(peris);
pll::PLL::new(pll::PllSys).configure(1, 1500_000_000, 6, 2);
pll::PLL::new(pll::PllUsb).configure(1, 480_000_000, 5, 2);
// Activate peripheral clock and take external oscillator as input
pac::CLOCKS.clk_peri_ctrl().write(|w| {
w.set_enable(true);
w.set_auxsrc(pac::clocks::vals::ClkPeriCtrlAuxsrc::XOSC_CLKSRC);
});
}

173
embassy-rp/src/uart.rs Normal file
View File

@ -0,0 +1,173 @@
use core::marker::PhantomData;
use embassy::util::PeripheralBorrow;
use embassy_extras::unborrow;
use gpio::Pin;
use crate::{gpio, pac, peripherals};
#[non_exhaustive]
pub struct Config {
pub baudrate: u32,
pub data_bits: u8,
pub stop_bits: u8,
}
impl Default for Config {
fn default() -> Self {
Self {
baudrate: 115200,
data_bits: 8,
stop_bits: 1,
}
}
}
pub struct Uart<'d, T: Instance> {
inner: T,
phantom: PhantomData<&'d mut T>,
}
impl<'d, T: Instance> Uart<'d, T> {
pub fn new(
inner: impl PeripheralBorrow<Target = T>,
tx: impl PeripheralBorrow<Target = impl TxPin<T>>,
rx: impl PeripheralBorrow<Target = impl RxPin<T>>,
cts: impl PeripheralBorrow<Target = impl CtsPin<T>>,
rts: impl PeripheralBorrow<Target = impl RtsPin<T>>,
config: Config,
) -> Self {
unborrow!(inner, tx, rx, cts, rts);
unsafe {
let p = inner.regs();
// todo get this from somewhere
let clk_base = 12_000_000;
let baud_rate_div = (8 * clk_base) / config.baudrate;
let mut baud_ibrd = baud_rate_div >> 7;
let mut baud_fbrd = ((baud_rate_div & 0x7f) + 1) / 2;
if baud_ibrd == 0 {
baud_ibrd = 1;
baud_fbrd = 0;
} else if baud_ibrd >= 65535 {
baud_ibrd = 65535;
baud_fbrd = 0;
}
// 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.uartlcr_h().write(|w| {
w.set_wlen(config.data_bits - 5);
w.set_stp2(config.stop_bits == 2);
w.set_pen(false);
w.set_eps(false);
w.set_fen(true);
});
p.uartcr().write(|w| {
w.set_uarten(true);
w.set_rxe(true);
w.set_txe(true);
});
tx.io().ctrl().write(|w| w.set_funcsel(2));
rx.io().ctrl().write(|w| w.set_funcsel(2));
cts.io().ctrl().write(|w| w.set_funcsel(2));
rts.io().ctrl().write(|w| w.set_funcsel(2));
}
Self {
inner,
phantom: PhantomData,
}
}
pub fn send(&mut self, data: &[u8]) {
unsafe {
let p = self.inner.regs();
for &byte in data {
if !p.uartfr().read().txff() {
p.uartdr().write(|w| w.set_data(byte));
}
}
}
}
}
mod sealed {
use super::*;
pub trait Instance {
fn regs(&self) -> pac::uart::Uart;
}
pub trait TxPin<T: Instance> {}
pub trait RxPin<T: Instance> {}
pub trait CtsPin<T: Instance> {}
pub trait RtsPin<T: Instance> {}
}
pub trait Instance: sealed::Instance {}
macro_rules! impl_instance {
($type:ident, $irq:ident) => {
impl sealed::Instance for peripherals::$type {
fn regs(&self) -> pac::uart::Uart {
pac::$type
}
}
impl Instance for peripherals::$type {}
};
}
impl_instance!(UART0, UART0);
impl_instance!(UART1, UART1);
pub trait TxPin<T: Instance>: sealed::TxPin<T> + Pin {}
pub trait RxPin<T: Instance>: sealed::RxPin<T> + Pin {}
pub trait CtsPin<T: Instance>: sealed::CtsPin<T> + Pin {}
pub trait RtsPin<T: Instance>: sealed::RtsPin<T> + Pin {}
macro_rules! impl_pin {
($pin:ident, $instance:ident, $function:ident) => {
impl sealed::$function<peripherals::$instance> for peripherals::$pin {}
impl $function<peripherals::$instance> for peripherals::$pin {}
};
}
impl_pin!(PIN_0, UART0, TxPin);
impl_pin!(PIN_1, UART0, RxPin);
impl_pin!(PIN_2, UART0, CtsPin);
impl_pin!(PIN_3, UART0, RtsPin);
impl_pin!(PIN_4, UART1, TxPin);
impl_pin!(PIN_5, UART1, RxPin);
impl_pin!(PIN_6, UART1, CtsPin);
impl_pin!(PIN_7, UART1, RtsPin);
impl_pin!(PIN_8, UART1, TxPin);
impl_pin!(PIN_9, UART1, RxPin);
impl_pin!(PIN_10, UART1, CtsPin);
impl_pin!(PIN_11, UART1, RtsPin);
impl_pin!(PIN_12, UART0, TxPin);
impl_pin!(PIN_13, UART0, RxPin);
impl_pin!(PIN_14, UART0, CtsPin);
impl_pin!(PIN_15, UART0, RtsPin);
impl_pin!(PIN_16, UART0, TxPin);
impl_pin!(PIN_17, UART0, RxPin);
impl_pin!(PIN_18, UART0, CtsPin);
impl_pin!(PIN_19, UART0, RtsPin);
impl_pin!(PIN_20, UART1, TxPin);
impl_pin!(PIN_21, UART1, RxPin);
impl_pin!(PIN_22, UART1, CtsPin);
impl_pin!(PIN_23, UART1, RtsPin);
impl_pin!(PIN_24, UART1, TxPin);
impl_pin!(PIN_25, UART1, RxPin);
impl_pin!(PIN_26, UART1, CtsPin);
impl_pin!(PIN_27, UART1, RtsPin);
impl_pin!(PIN_28, UART0, TxPin);
impl_pin!(PIN_29, UART0, RxPin);