diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index 49c8c8e1130..b81fec44231 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -369,6 +369,8 @@ jobs: include: - feature: pico-st7789 target: thumbv6m-none-eabi + - feature: pico2-st7789 + target: thumbv8m.main-none-eabihf - feature: stm32h735g target: thumbv7em-none-eabihf steps: diff --git a/examples/mcu-board-support/Cargo.toml b/examples/mcu-board-support/Cargo.toml index 128da6f35f2..8a0c121b826 100644 --- a/examples/mcu-board-support/Cargo.toml +++ b/examples/mcu-board-support/Cargo.toml @@ -19,6 +19,7 @@ path = "lib.rs" [features] pico-st7789 = ["slint/unsafe-single-threaded", "rp-pico", "embedded-hal", "embedded-hal-nb", "cortex-m-rt", "embedded-alloc", "fugit", "cortex-m", "display-interface", "display-interface-spi", "mipidsi", "defmt", "defmt-rtt", "slint/libm", "embedded-dma", "embedded-graphics", "euclid/libm"] +pico2-st7789 = ["slint/unsafe-single-threaded", "rp235x-hal/binary-info", "rp235x-hal/critical-section-impl", "rp235x-hal/rt", "rp235x-hal/defmt", "embedded-hal", "embedded-hal-nb", "cortex-m-rt", "embedded-alloc", "fugit", "cortex-m", "display-interface", "display-interface-spi", "mipidsi", "defmt", "defmt-rtt", "slint/libm", "embedded-dma", "embedded-graphics", "euclid/libm"] stm32h735g = ["slint/unsafe-single-threaded", "cortex-m/critical-section-single-core", "cortex-m-rt","embedded-alloc", "embedded-time", "stm32h7xx-hal/stm32h735", "defmt", "defmt-rtt", "embedded-display-controller", "ft5336", "panic-probe", "slint/libm", "getrandom"] esp32-s2-kaluga-1 = ["slint/unsafe-single-threaded", "esp-hal/esp32s2", "embedded-hal", "embedded-hal-bus", "esp-alloc", "esp-println/esp32s2", "display-interface", "display-interface-spi", "mipidsi", "embedded-graphics-core", "slint/libm"] esp32-s3-box = ["slint/unsafe-single-threaded", "esp-hal/esp32s3", "embedded-hal", "embedded-hal-bus", "esp-alloc", "esp-println/esp32s3", "esp-backtrace/esp32s3", "display-interface", "display-interface-spi", "mipidsi", "embedded-graphics-core", "slint/libm", "tt21100"] @@ -43,6 +44,7 @@ embedded-hal-nb = { version = "1.0.0", optional = true } embedded-hal-bus = { version = "0.2", optional = true } embedded-dma = { version = "0.2.0", optional = true } rp-pico = { version = "0.9.0", optional = true } +rp235x-hal = { version = "0.2.0", default-features = false, optional = true } fugit = { version = "0.3.6", optional = true } euclid = { version = "0.22", default-features = false, optional = true } diff --git a/examples/mcu-board-support/README.md b/examples/mcu-board-support/README.md index 1ee83e9cef6..8d0bfd5fedf 100644 --- a/examples/mcu-board-support/README.md +++ b/examples/mcu-board-support/README.md @@ -74,6 +74,28 @@ udisksctl mount -b /dev/sda1 elf2uf2-rs -d target/thumbv6m-none-eabi/release/printerdemo_mcu ``` +### On the Raspberry Pi Pico2 + +Build the demo with: + +```sh +cargo build -p printerdemo_mcu --no-default-features --features=mcu-board-support/pico2-st7789 --target=thumbv8m.main-none-eabihf --release +``` + +The resulting file can be flashed conveniently with [picotool](https://github.com/raspberrypi/picotool). You should build it from source. + +Then upload the demo to the Raspberry Pi Pico: push the "bootsel" white button on the device while connecting the +micro-usb cable to the device, this connects some USB storage on your workstation where you can store the binary. + +Or from the command on linux (connect the device while pressing the "bootsel" button): + +```sh +# If you're on Linux: mount the device +udisksctl mount -b /dev/sda1 +# upload +picotool load -u -v -x -t elf target/thumbv8m.main-none-eabihf/release/printerdemo_mcu +``` + #### Using probe-rs This requires [probe-rs](https://probe.rs) and to connect the pico via a probe diff --git a/examples/mcu-board-support/build.rs b/examples/mcu-board-support/build.rs index d9aaf0ff949..31998a52edf 100644 --- a/examples/mcu-board-support/build.rs +++ b/examples/mcu-board-support/build.rs @@ -8,6 +8,8 @@ fn main() -> std::io::Result<()> { cfg_if::cfg_if! { if #[cfg(feature = "pico-st7789")] { board_config_path = Some([env!("CARGO_MANIFEST_DIR"), "pico_st7789", "board_config.toml"].iter().collect()); + } else if #[cfg(feature = "pico2-st7789")] { + board_config_path = Some([env!("CARGO_MANIFEST_DIR"), "pico2_st7789", "board_config.toml"].iter().collect()); } else if #[cfg(feature = "stm32h735g")] { board_config_path = Some([env!("CARGO_MANIFEST_DIR"), "stm32h735g", "board_config.toml"].iter().collect()); } diff --git a/examples/mcu-board-support/lib.rs b/examples/mcu-board-support/lib.rs index cbb130a7f94..ad52103c277 100644 --- a/examples/mcu-board-support/lib.rs +++ b/examples/mcu-board-support/lib.rs @@ -14,6 +14,11 @@ mod pico_st7789; #[cfg(feature = "pico-st7789")] pub use pico_st7789::*; +#[cfg(feature = "pico2-st7789")] +mod pico2_st7789; +#[cfg(feature = "pico2-st7789")] +pub use pico2_st7789::*; + #[cfg(feature = "stm32h735g")] mod stm32h735g; #[cfg(feature = "stm32h735g")] @@ -31,6 +36,7 @@ pub use esp32_s3_box::*; #[cfg(not(any( feature = "pico-st7789", + feature = "pico2-st7789", feature = "stm32h735g", feature = "esp32-s2-kaluga-1", feature = "esp32-s3-box" @@ -39,6 +45,7 @@ pub use i_slint_core_macros::identity as entry; #[cfg(not(any( feature = "pico-st7789", + feature = "pico2-st7789", feature = "stm32h735g", feature = "esp32-s2-kaluga-1", feature = "esp32-s3-box" diff --git a/examples/mcu-board-support/pico2_st7789.rs b/examples/mcu-board-support/pico2_st7789.rs new file mode 100644 index 00000000000..f92230e1865 --- /dev/null +++ b/examples/mcu-board-support/pico2_st7789.rs @@ -0,0 +1,677 @@ +// Copyright © SixtyFPS GmbH +// SPDX-License-Identifier: MIT + +extern crate alloc; + +use alloc::boxed::Box; +use alloc::rc::Rc; +use alloc::vec; +use core::cell::RefCell; +use core::convert::Infallible; +use cortex_m::interrupt::Mutex; +use cortex_m::singleton; +pub use cortex_m_rt::entry; +use defmt_rtt as _; +use embedded_alloc::LlffHeap as Heap; +use embedded_hal::digital::{InputPin, OutputPin}; +use embedded_hal::spi::{ErrorType, Operation, SpiBus, SpiDevice}; +use fugit::{Hertz, RateExtU32}; +use hal::dma::{DMAExt, SingleChannel, WriteTarget}; +use hal::gpio::{self, Interrupt as GpioInterrupt}; +use hal::timer::{Alarm, Alarm0}; +use pac::interrupt; +#[cfg(feature = "panic-probe")] +use panic_probe as _; +use renderer::Rgb565Pixel; + +mod rp_pico2; +use rp_pico2::hal::{self, pac, prelude::*, timer::CopyableTimer0, Timer}; +use slint::platform::{software_renderer as renderer, PointerEventButton, WindowEvent}; + +const HEAP_SIZE: usize = 200 * 1024; +static mut HEAP: [u8; HEAP_SIZE] = [0; HEAP_SIZE]; + +#[global_allocator] +static ALLOCATOR: Heap = Heap::empty(); + +type IrqPin = gpio::Pin, gpio::PullUp>; +static IRQ_PIN: Mutex>> = Mutex::new(RefCell::new(None)); + +static ALARM0: Mutex>>> = Mutex::new(RefCell::new(None)); +static TIMER: Mutex>>> = Mutex::new(RefCell::new(None)); + +// 16ns for serial clock cycle (write), page 43 of https://www.waveshare.com/w/upload/a/ae/ST7789_Datasheet.pdf +const SPI_ST7789VW_MAX_FREQ: Hertz = Hertz::::Hz(62_500_000); + +const DISPLAY_SIZE: slint::PhysicalSize = slint::PhysicalSize::new(320, 240); + +/// The Pixel type of the backing store +pub type TargetPixel = Rgb565Pixel; + +type SpiPins = ( + gpio::Pin, + gpio::Pin, + gpio::Pin, +); + +type EnabledSpi = hal::Spi; +type SpiRefCell = RefCell<(EnabledSpi, Hertz)>; +type Display = mipidsi::Display; + +#[derive(Clone)] +struct SharedSpiWithFreq { + refcell: &'static SpiRefCell, + cs: CS, + freq: Hertz, +} + +impl ErrorType for SharedSpiWithFreq { + type Error = ::Error; +} + +impl> SpiDevice for SharedSpiWithFreq { + #[inline] + fn transaction(&mut self, operations: &mut [Operation]) -> Result<(), Self::Error> { + let mut borrowed = self.refcell.borrow_mut(); + if borrowed.1 != self.freq { + borrowed.0.flush()?; + // the touchscreen and the LCD have different frequencies + borrowed.0.set_baudrate(125_000_000u32.Hz(), self.freq); + borrowed.1 = self.freq; + } + self.cs.set_low()?; + for op in operations { + match op { + Operation::Read(words) => borrowed.0.read(words), + Operation::Write(words) => borrowed.0.write(words), + Operation::Transfer(read, write) => borrowed.0.transfer(read, write), + Operation::TransferInPlace(words) => borrowed.0.transfer_in_place(words), + Operation::DelayNs(_) => unimplemented!(), + }?; + } + borrowed.0.flush()?; + drop(borrowed); + self.cs.set_high()?; + Ok(()) + } +} + +pub fn init() { + let mut pac = pac::Peripherals::take().unwrap(); + + let mut watchdog = hal::watchdog::Watchdog::new(pac.WATCHDOG); + let clocks = hal::clocks::init_clocks_and_plls( + rp_pico2::XOSC_CRYSTAL_FREQ, + pac.XOSC, + pac.CLOCKS, + pac.PLL_SYS, + pac.PLL_USB, + &mut pac.RESETS, + &mut watchdog, + ) + .ok() + .unwrap(); + + unsafe { ALLOCATOR.init(core::ptr::addr_of_mut!(HEAP) as usize, HEAP_SIZE) } + + let mut timer = hal::Timer::new_timer0(pac.TIMER0, &mut pac.RESETS, &clocks); + + let sio = hal::sio::Sio::new(pac.SIO); + let pins = rp_pico2::Pins::new(pac.IO_BANK0, pac.PADS_BANK0, sio.gpio_bank0, &mut pac.RESETS); + + let mut touch_cs = pins.gpio16.into_push_pull_output(); + touch_cs.set_high().unwrap(); + let touch_irq = pins.gpio17.into_pull_up_input(); + touch_irq.set_interrupt_enabled(GpioInterrupt::LevelLow, true); + cortex_m::interrupt::free(|cs| { + IRQ_PIN.borrow(cs).replace(Some(touch_irq)); + }); + + let rst = pins.gpio15.into_push_pull_output(); + let mut backlight = pins.gpio13.into_push_pull_output(); + + let dc = pins.gpio8.into_push_pull_output(); + let cs = pins.gpio9.into_push_pull_output(); + + let spi_sclk = pins.gpio10.into_function::(); + let spi_mosi = pins.gpio11.into_function::(); + let spi_miso = pins.gpio12.into_function::(); + + let spi = hal::Spi::new(pac.SPI1, (spi_mosi, spi_miso, spi_sclk)); + let spi = spi.init( + &mut pac.RESETS, + clocks.peripheral_clock.freq(), + SPI_ST7789VW_MAX_FREQ, + &embedded_hal::spi::MODE_3, + ); + + // SAFETY: This is not safe :-( But we need to access the SPI and its control pins for the PIO + let (dc_copy, cs_copy) = + unsafe { (core::ptr::read(&dc as *const _), core::ptr::read(&cs as *const _)) }; + let stolen_spi = unsafe { core::ptr::read(&spi as *const _) }; + + let spi = singleton!(:SpiRefCell = SpiRefCell::new((spi, 0.Hz()))).unwrap(); + + let display_spi = SharedSpiWithFreq { refcell: spi, cs, freq: SPI_ST7789VW_MAX_FREQ }; + let di = display_interface_spi::SPIInterface::new(display_spi, dc); + let display = mipidsi::Builder::new(mipidsi::models::ST7789, di) + .reset_pin(rst) + .display_size(DISPLAY_SIZE.height as _, DISPLAY_SIZE.width as _) + .orientation(mipidsi::options::Orientation::new().rotate(mipidsi::options::Rotation::Deg90)) + .invert_colors(mipidsi::options::ColorInversion::Inverted) + .init(&mut timer) + .unwrap(); + backlight.set_high().unwrap(); + + let touch = xpt2046::XPT2046::new( + &IRQ_PIN, + SharedSpiWithFreq { refcell: spi, cs: touch_cs, freq: xpt2046::SPI_FREQ }, + ) + .unwrap(); + + let mut alarm0 = timer.alarm_0().unwrap(); + alarm0.enable_interrupt(); + + cortex_m::interrupt::free(|cs| { + ALARM0.borrow(cs).replace(Some(alarm0)); + TIMER.borrow(cs).replace(Some(timer)); + }); + + unsafe { + cortex_m::peripheral::NVIC::unmask(pac::Interrupt::IO_IRQ_BANK0); + cortex_m::peripheral::NVIC::unmask(pac::Interrupt::TIMER0_IRQ_0); + } + + let dma = pac.DMA.split(&mut pac.RESETS); + let pio = PioTransfer::Idle( + dma.ch0, + vec![Rgb565Pixel::default(); DISPLAY_SIZE.width as _].leak(), + stolen_spi, + ); + let buffer_provider = DrawBuffer { + display, + buffer: vec![Rgb565Pixel::default(); DISPLAY_SIZE.width as _].leak(), + pio: Some(pio), + stolen_pin: (dc_copy, cs_copy), + }; + + slint::platform::set_platform(Box::new(PicoBackend { + window: Default::default(), + buffer_provider: buffer_provider.into(), + touch: touch.into(), + })) + .expect("backend already initialized"); +} + +struct PicoBackend { + window: RefCell>>, + buffer_provider: RefCell, + touch: RefCell, +} + +impl< + DI: display_interface::WriteOnlyDataCommand, + RST: OutputPin, + TO: WriteTarget + embedded_hal_nb::spi::FullDuplex, + CH: SingleChannel, + DC_: OutputPin, + CS_: OutputPin, + IRQ: InputPin, + SPI: SpiDevice, + > slint::platform::Platform + for PicoBackend< + DrawBuffer, PioTransfer, (DC_, CS_)>, + xpt2046::XPT2046, + > +{ + fn create_window_adapter( + &self, + ) -> Result, slint::PlatformError> { + let window = + renderer::MinimalSoftwareWindow::new(renderer::RepaintBufferType::ReusedBuffer); + self.window.replace(Some(window.clone())); + Ok(window) + } + + fn duration_since_start(&self) -> core::time::Duration { + let counter = cortex_m::interrupt::free(|cs| { + TIMER.borrow(cs).borrow().as_ref().map(|t| t.get_counter().ticks()).unwrap_or_default() + }); + core::time::Duration::from_micros(counter) + } + + fn run_event_loop(&self) -> Result<(), slint::PlatformError> { + let mut last_touch = None; + + self.window.borrow().as_ref().unwrap().set_size(DISPLAY_SIZE); + + loop { + slint::platform::update_timers_and_animations(); + + if let Some(window) = self.window.borrow().clone() { + window.draw_if_needed(|renderer| { + let mut buffer_provider = self.buffer_provider.borrow_mut(); + renderer.render_by_line(&mut *buffer_provider); + buffer_provider.flush_frame(); + }); + + // handle touch event + let button = PointerEventButton::Left; + if let Some(event) = self + .touch + .borrow_mut() + .read() + .map_err(|_| ()) + .unwrap() + .map(|point| { + let position = slint::PhysicalPosition::new( + (point.x * DISPLAY_SIZE.width as f32) as _, + (point.y * DISPLAY_SIZE.height as f32) as _, + ) + .to_logical(window.scale_factor()); + match last_touch.replace(position) { + Some(_) => WindowEvent::PointerMoved { position }, + None => WindowEvent::PointerPressed { position, button }, + } + }) + .or_else(|| { + last_touch + .take() + .map(|position| WindowEvent::PointerReleased { position, button }) + }) + { + let is_pointer_release_event = + matches!(event, WindowEvent::PointerReleased { .. }); + + window.dispatch_event(event); + + // removes hover state on widgets + if is_pointer_release_event { + window.dispatch_event(WindowEvent::PointerExited); + } + // Don't go to sleep after a touch event that forces a redraw + continue; + } + + if window.has_active_animations() { + continue; + } + } + + let sleep_duration = match slint::platform::duration_until_next_timer_update() { + None => None, + Some(d) => { + let micros = d.as_micros() as u32; + if micros < 10 { + // Cannot wait for less than 10µs, or `schedule()` panics + continue; + } else { + Some(fugit::MicrosDurationU32::micros(micros)) + } + } + }; + + cortex_m::interrupt::free(|cs| { + if let Some(duration) = sleep_duration { + ALARM0.borrow(cs).borrow_mut().as_mut().unwrap().schedule(duration).unwrap(); + } + + IRQ_PIN + .borrow(cs) + .borrow() + .as_ref() + .unwrap() + .set_interrupt_enabled(GpioInterrupt::LevelLow, true); + }); + cortex_m::asm::wfe(); + } + } + + fn debug_log(&self, arguments: core::fmt::Arguments) { + use alloc::string::ToString; + defmt::println!("{=str}", arguments.to_string()); + } +} + +enum PioTransfer { + Idle(CH, &'static mut [TargetPixel], TO), + Running(hal::dma::single_buffer::Transfer), +} + +impl, CH: SingleChannel> PioTransfer { + fn wait(self) -> (CH, &'static mut [TargetPixel], TO) { + match self { + PioTransfer::Idle(a, b, c) => (a, b, c), + PioTransfer::Running(dma) => { + let (a, b, to) = dma.wait(); + (a, b.0, to) + } + } + } +} + +struct DrawBuffer { + display: Display, + buffer: &'static mut [TargetPixel], + pio: Option, + stolen_pin: Stolen, +} + +impl< + DI: display_interface::WriteOnlyDataCommand, + RST: OutputPin, + TO: WriteTarget, + CH: SingleChannel, + DC_: OutputPin, + CS_: OutputPin, + > renderer::LineBufferProvider + for &mut DrawBuffer, PioTransfer, (DC_, CS_)> +{ + type TargetPixel = TargetPixel; + + fn process_line( + &mut self, + line: usize, + range: core::ops::Range, + render_fn: impl FnOnce(&mut [TargetPixel]), + ) { + render_fn(&mut self.buffer[range.clone()]); + + /* -- Send the pixel without DMA + self.display.set_pixels( + range.start as _, + line as _, + range.end as _, + line as _, + self.buffer[range.clone()] + .iter() + .map(|x| embedded_graphics::pixelcolor::raw::RawU16::new(x.0).into()), + ); + return;*/ + + // convert from little to big endian before sending to the DMA channel + for x in &mut self.buffer[range.clone()] { + *x = Rgb565Pixel(x.0.to_be()) + } + let (ch, mut b, spi) = self.pio.take().unwrap().wait(); + core::mem::swap(&mut self.buffer, &mut b); + + // We send empty data just to get the device in the right window + self.display + .set_pixels( + range.start as u16, + line as _, + range.end as u16, + line as u16, + core::iter::empty(), + ) + .unwrap(); + + self.stolen_pin.1.set_low().unwrap(); + self.stolen_pin.0.set_high().unwrap(); + let mut dma = hal::dma::single_buffer::Config::new(ch, PartialReadBuffer(b, range), spi); + dma.pace(hal::dma::Pace::PreferSink); + self.pio = Some(PioTransfer::Running(dma.start())); + /*let (a, b, c) = dma.start().wait(); + self.pio = Some(PioTransfer::Idle(a, b.0, c));*/ + } +} + +impl< + DI: display_interface::WriteOnlyDataCommand, + RST: OutputPin, + TO: WriteTarget + embedded_hal_nb::spi::FullDuplex, + CH: SingleChannel, + DC_: OutputPin, + CS_: OutputPin, + > DrawBuffer, PioTransfer, (DC_, CS_)> +{ + fn flush_frame(&mut self) { + let (ch, b, mut spi) = self.pio.take().unwrap().wait(); + self.stolen_pin.1.set_high().unwrap(); + + // After the DMA operated, we need to empty the receive FIFO, otherwise the touch screen + // driver will pick wrong values. + // Continue to read as long as we don't get a Err(WouldBlock) + while !spi.read().is_err() {} + + self.pio = Some(PioTransfer::Idle(ch, b, spi)); + } +} + +struct PartialReadBuffer(&'static mut [Rgb565Pixel], core::ops::Range); +unsafe impl embedded_dma::ReadBuffer for PartialReadBuffer { + type Word = u8; + + unsafe fn read_buffer(&self) -> (*const ::Word, usize) { + let act_slice = &self.0[self.1.clone()]; + (act_slice.as_ptr() as *const u8, act_slice.len() * core::mem::size_of::()) + } +} + +mod xpt2046 { + use core::cell::RefCell; + use cortex_m::interrupt::Mutex; + use embedded_hal::digital::InputPin; + use embedded_hal::spi::SpiDevice; + use euclid::default::Point2D; + use fugit::Hertz; + + pub const SPI_FREQ: Hertz = Hertz::::Hz(3_000_000); + + pub struct XPT2046 { + irq: &'static Mutex>>, + spi: SPI, + pressed: bool, + } + + impl, SPI: SpiDevice> XPT2046 { + pub fn new(irq: &'static Mutex>>, spi: SPI) -> Result { + Ok(Self { irq, spi, pressed: false }) + } + + pub fn read(&mut self) -> Result>, Error> { + const PRESS_THRESHOLD: i32 = -25_000; + const RELEASE_THRESHOLD: i32 = -30_000; + let threshold = if self.pressed { RELEASE_THRESHOLD } else { PRESS_THRESHOLD }; + self.pressed = false; + + if cortex_m::interrupt::free(|cs| { + self.irq.borrow(cs).borrow_mut().as_mut().unwrap().is_low() + }) + .map_err(|e| Error::Pin(e))? + { + const CMD_X_READ: u8 = 0b10010000; + const CMD_Y_READ: u8 = 0b11010000; + const CMD_Z1_READ: u8 = 0b10110000; + const CMD_Z2_READ: u8 = 0b11000000; + + // These numbers were measured approximately. + const MIN_X: u32 = 1900; + const MAX_X: u32 = 30300; + const MIN_Y: u32 = 2300; + const MAX_Y: u32 = 30300; + + macro_rules! xchg { + ($byte:expr) => {{ + let mut b = [0, $byte, 0, 0]; + self.spi.transfer_in_place(&mut b).map_err(|e| Error::Transfer(e))?; + let [_, _, h, l] = b; + ((h as u32) << 8) | (l as u32) + }}; + } + + let z1 = xchg!(CMD_Z1_READ); + let z2 = xchg!(CMD_Z2_READ); + let z = z1 as i32 - z2 as i32; + + if z < threshold { + return Ok(None); + } + + let mut point = Point2D::new(0u32, 0u32); + for _ in 0..10 { + let y = xchg!(CMD_Y_READ); + let x = xchg!(CMD_X_READ); + point += euclid::vec2(i16::MAX as u32 - x, y) + } + point /= 10; + + let z1 = xchg!(CMD_Z1_READ); + let z2 = xchg!(CMD_Z2_READ); + let z = z1 as i32 - z2 as i32; + + if z < RELEASE_THRESHOLD { + return Ok(None); + } + + self.pressed = true; + Ok(Some(euclid::point2( + point.x.saturating_sub(MIN_X) as f32 / (MAX_X - MIN_X) as f32, + point.y.saturating_sub(MIN_Y) as f32 / (MAX_Y - MIN_Y) as f32, + ))) + } else { + Ok(None) + } + } + } + + pub enum Error { + Pin(PinE), + Transfer(TransferE), + } +} + +#[interrupt] +fn IO_IRQ_BANK0() { + cortex_m::interrupt::free(|cs| { + let mut pin = IRQ_PIN.borrow(cs).borrow_mut(); + let pin = pin.as_mut().unwrap(); + pin.set_interrupt_enabled(GpioInterrupt::LevelLow, false); + pin.clear_interrupt(GpioInterrupt::LevelLow); + }); +} + +#[interrupt] +fn TIMER0_IRQ_0() { + cortex_m::interrupt::free(|cs| { + ALARM0.borrow(cs).borrow_mut().as_mut().unwrap().clear_interrupt(); + }); +} + +#[cfg(not(feature = "panic-probe"))] +#[inline(never)] +#[panic_handler] +fn panic(info: &core::panic::PanicInfo) -> ! { + // Safety: it's ok to steal here since we are in the panic handler, and the rest of the code will not be run anymore + let mut pac = unsafe { pac::Peripherals::steal() }; + + let sio = hal::sio::Sio::new(pac.SIO); + let pins = rp_pico2::Pins::new(pac.IO_BANK0, pac.PADS_BANK0, sio.gpio_bank0, &mut pac.RESETS); + let mut led = pins.led.into_push_pull_output(); + led.set_high().unwrap(); + + // Re-init the display + let mut watchdog = hal::watchdog::Watchdog::new(pac.WATCHDOG); + let clocks = hal::clocks::init_clocks_and_plls( + rp_pico2::XOSC_CRYSTAL_FREQ, + pac.XOSC, + pac.CLOCKS, + pac.PLL_SYS, + pac.PLL_USB, + &mut pac.RESETS, + &mut watchdog, + ) + .ok() + .unwrap(); + + let spi_sclk = pins.gpio10.into_function::(); + let spi_mosi = pins.gpio11.into_function::(); + let spi_miso = pins.gpio12.into_function::(); + + let spi = hal::Spi::<_, _, _, 8>::new(pac.SPI1, (spi_mosi, spi_miso, spi_sclk)); + let spi = spi.init( + &mut pac.RESETS, + clocks.peripheral_clock.freq(), + 4_000_000u32.Hz(), + &embedded_hal::spi::MODE_3, + ); + + let mut timer = Timer::new_timer0(pac.TIMER0, &mut pac.RESETS, &clocks); + + let rst = pins.gpio15.into_push_pull_output(); + let mut bl = pins.gpio13.into_push_pull_output(); + let dc = pins.gpio8.into_push_pull_output(); + let cs = pins.gpio9.into_push_pull_output(); + bl.set_high().unwrap(); + let spi = singleton!(:SpiRefCell = SpiRefCell::new((spi, 0.Hz()))).unwrap(); + let display_spi = SharedSpiWithFreq { refcell: spi, cs, freq: SPI_ST7789VW_MAX_FREQ }; + let di = display_interface_spi::SPIInterface::new(display_spi, dc); + let mut display = mipidsi::Builder::new(mipidsi::models::ST7789, di) + .reset_pin(rst) + .display_size(DISPLAY_SIZE.height as _, DISPLAY_SIZE.width as _) + .orientation(mipidsi::options::Orientation::new().rotate(mipidsi::options::Rotation::Deg90)) + .invert_colors(mipidsi::options::ColorInversion::Inverted) + .init(&mut timer) + .unwrap(); + + use core::fmt::Write; + use embedded_graphics::{ + mono_font::{ascii::FONT_6X10, MonoTextStyle}, + pixelcolor::Rgb565, + prelude::*, + text::Text, + }; + + display.fill_solid(&display.bounding_box(), Rgb565::new(0x00, 0x25, 0xff)).unwrap(); + + struct WriteToScreen<'a, D> { + x: i32, + y: i32, + width: i32, + style: MonoTextStyle<'a, Rgb565>, + display: &'a mut D, + } + let mut writer = WriteToScreen { + x: 0, + y: 1, + width: display.bounding_box().size.width as i32 / 6 - 1, + style: MonoTextStyle::new(&FONT_6X10, Rgb565::WHITE), + display: &mut display, + }; + impl<'a, D: DrawTarget> Write for WriteToScreen<'a, D> { + fn write_str(&mut self, mut s: &str) -> Result<(), core::fmt::Error> { + while !s.is_empty() { + let (x, y) = (self.x, self.y); + let end_of_line = s + .find(|c| { + if c == '\n' || self.x > self.width { + self.x = 0; + self.y += 1; + true + } else { + self.x += 1; + false + } + }) + .unwrap_or(s.len()); + let (line, rest) = s.split_at(end_of_line); + let sz = self.style.font.character_size; + Text::new(line, Point::new(x * sz.width as i32, y * sz.height as i32), self.style) + .draw(self.display) + .map_err(|_| core::fmt::Error)?; + s = rest.strip_prefix('\n').unwrap_or(rest); + } + Ok(()) + } + } + write!(writer, "{}", info).unwrap(); + + loop { + use embedded_hal::delay::DelayNs as _; + timer.delay_ms(100); + led.set_low().unwrap(); + timer.delay_ms(100); + led.set_high().unwrap(); + } +} diff --git a/examples/mcu-board-support/pico2_st7789/board_config.toml b/examples/mcu-board-support/pico2_st7789/board_config.toml new file mode 100644 index 00000000000..3ec4da5d6a4 --- /dev/null +++ b/examples/mcu-board-support/pico2_st7789/board_config.toml @@ -0,0 +1,16 @@ +# Copyright © SixtyFPS GmbH +# SPDX-License-Identifier: MIT + +link_args = [ + "--nmagic", + "-Tlink.x", + "-Tdefmt.x", +] + +rustflags = [ + "-C", "target-cpu=cortex-m33", +] + +link_search_path = [ + "." +] diff --git a/examples/mcu-board-support/pico2_st7789/memory.x b/examples/mcu-board-support/pico2_st7789/memory.x new file mode 100644 index 00000000000..a0538e19fed --- /dev/null +++ b/examples/mcu-board-support/pico2_st7789/memory.x @@ -0,0 +1,80 @@ +/* Copyright © 2021 rp-rs organization + SPDX-License-Identifier: MIT OR Apache-2.0 + Copied from https://github.com/rp-rs/rp-hal/blob/main/rp235x-hal-examples/memory.x +*/ + +MEMORY { + /* + * The RP2350 has either external or internal flash. + * + * 2 MiB is a safe default here, although a Pico 2 has 4 MiB. + */ + FLASH : ORIGIN = 0x10000000, LENGTH = 2048K + /* + * RAM consists of 8 banks, SRAM0-SRAM7, with a striped mapping. + * This is usually good for performance, as it distributes load on + * those banks evenly. + */ + RAM : ORIGIN = 0x20000000, LENGTH = 512K + /* + * RAM banks 8 and 9 use a direct mapping. They can be used to have + * memory areas dedicated for some specific job, improving predictability + * of access times. + * Example: Separate stacks for core0 and core1. + */ + SRAM4 : ORIGIN = 0x20080000, LENGTH = 4K + SRAM5 : ORIGIN = 0x20081000, LENGTH = 4K +} + +SECTIONS { + /* ### Boot ROM info + * + * Goes after .vector_table, to keep it in the first 4K of flash + * where the Boot ROM (and picotool) can find it + */ + .start_block : ALIGN(4) + { + __start_block_addr = .; + KEEP(*(.start_block)); + KEEP(*(.boot_info)); + } > FLASH + +} INSERT AFTER .vector_table; + +/* move .text to start /after/ the boot info */ +_stext = ADDR(.start_block) + SIZEOF(.start_block); + +SECTIONS { + /* ### Picotool 'Binary Info' Entries + * + * Picotool looks through this block (as we have pointers to it in our + * header) to find interesting information. + */ + .bi_entries : ALIGN(4) + { + /* We put this in the header */ + __bi_entries_start = .; + /* Here are the entries */ + KEEP(*(.bi_entries)); + /* Keep this block a nice round size */ + . = ALIGN(4); + /* We put this in the header */ + __bi_entries_end = .; + } > FLASH +} INSERT AFTER .text; + +SECTIONS { + /* ### Boot ROM extra info + * + * Goes after everything in our program, so it can contain a signature. + */ + .end_block : ALIGN(4) + { + __end_block_addr = .; + KEEP(*(.end_block)); + } > FLASH + +} INSERT AFTER .uninit; + +PROVIDE(start_to_end = __end_block_addr - __start_block_addr); +PROVIDE(end_to_start = __start_block_addr - __end_block_addr); diff --git a/examples/mcu-board-support/pico2_st7789/rp_pico2.rs b/examples/mcu-board-support/pico2_st7789/rp_pico2.rs new file mode 100644 index 00000000000..0caa1ed1dac --- /dev/null +++ b/examples/mcu-board-support/pico2_st7789/rp_pico2.rs @@ -0,0 +1,821 @@ +/* Copyright © 2021 rp-rs organization + SPDX-License-Identifier: MIT OR Apache-2.0 + Copied from https://github.com/rp-rs/rp-hal-boards/blob/main/boards/rp-pico/src/lib.rs + and slightly changed for RP2350 chip +*/ + +//! A Hardware Abstraction Layer for the Raspberry Pi Pico. +//! +//! This crate serves as a HAL (Hardware Abstraction Layer) for the Raspberry Pi Pico. Since the Raspberry Pi Pico +//! is based on the RP2350 chip, it re-exports the [rp235x_hal] crate which contains the tooling to work with the +//! rp2350 chip. +//! +//! # Examples: +//! +//! The following example turns on the onboard LED. Note that most of the logic works through the [rp235x_hal] crate. +//! ```ignore +//! #![no_main] +//! use rp_pico::entry; +//! use panic_halt as _; +//! use embedded_hal::digital::v2::OutputPin; +//! use rp_pico::hal::pac; +//! use rp_pico::hal; + +//! #[entry] +//! fn does_not_have_to_be_main() -> ! { +//! let mut pac = pac::Peripherals::take().unwrap(); +//! let sio = hal::Sio::new(pac.SIO); +//! let pins = rp_pico::Pins::new( +//! pac.IO_BANK0, +//! pac.PADS_BANK0, +//! sio.gpio_bank0, +//! &mut pac.RESETS, +//! ); +//! let mut led_pin = pins.led.into_push_pull_output(); +//! led_pin.set_high().unwrap(); +//! loop { +//! } +//! } +//! ``` + +pub extern crate rp235x_hal as hal; + +extern crate cortex_m_rt; + +/// The `entry` macro declares the starting function to the linker. +/// This is similar to the `main` function in console applications. +/// +/// It is based on the [cortex_m_rt](https://docs.rs/cortex-m-rt/latest/cortex_m_rt/attr.entry.html) crate. +/// +/// # Examples +/// ```ignore +/// #![no_std] +/// #![no_main] +/// use rp_pico::entry; +/// #[entry] +/// fn you_can_use_a_custom_main_name_here() -> ! { +/// loop {} +/// } +/// ``` +#[allow(unused_imports)] +pub use hal::entry; + +#[link_section = ".start_block"] +#[no_mangle] +#[used] +pub static BOOT2_FIRMWARE: hal::block::ImageDef = hal::block::ImageDef::secure_exe(); + +#[allow(unused_imports)] +pub use hal::pac; + +hal::bsp_pins!( + /// GPIO 0 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI0 RX` | [crate::Gp0Spi0Rx] | + /// | `UART0 TX` | [crate::Gp0Uart0Tx] | + /// | `I2C0 SDA` | [crate::Gp0I2C0Sda] | + /// | `PWM0 A` | [crate::Gp0Pwm0A] | + /// | `PIO0` | [crate::Gp0Pio0] | + /// | `PIO1` | [crate::Gp0Pio1] | + Gpio0 { + name: gpio0, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio0]. + FunctionUart, PullNone: Gp0Uart0Tx, + /// SPI Function alias for pin [crate::Pins::gpio0]. + FunctionSpi, PullNone: Gp0Spi0Rx, + /// I2C Function alias for pin [crate::Pins::gpio0]. + FunctionI2C, PullUp: Gp0I2C0Sda, + /// PWM Function alias for pin [crate::Pins::gpio0]. + FunctionPwm, PullNone: Gp0Pwm0A, + /// PIO0 Function alias for pin [crate::Pins::gpio0]. + FunctionPio0, PullNone: Gp0Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio0]. + FunctionPio1, PullNone: Gp0Pio1 + } + }, + + /// GPIO 1 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI0 CSn` | [crate::Gp1Spi0Csn] | + /// | `UART0 RX` | [crate::Gp1Uart0Rx] | + /// | `I2C0 SCL` | [crate::Gp1I2C0Scl] | + /// | `PWM0 B` | [crate::Gp1Pwm0B] | + /// | `PIO0` | [crate::Gp1Pio0] | + /// | `PIO1` | [crate::Gp1Pio1] | + Gpio1 { + name: gpio1, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio1]. + FunctionUart, PullNone: Gp1Uart0Rx, + /// SPI Function alias for pin [crate::Pins::gpio1]. + FunctionSpi, PullNone: Gp1Spi0Csn, + /// I2C Function alias for pin [crate::Pins::gpio1]. + FunctionI2C, PullUp: Gp1I2C0Scl, + /// PWM Function alias for pin [crate::Pins::gpio1]. + FunctionPwm, PullNone: Gp1Pwm0B, + /// PIO0 Function alias for pin [crate::Pins::gpio1]. + FunctionPio0, PullNone: Gp1Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio1]. + FunctionPio1, PullNone: Gp1Pio1 + } + }, + + /// GPIO 2 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI0 SCK` | [crate::Gp2Spi0Sck] | + /// | `UART0 CTS` | [crate::Gp2Uart0Cts] | + /// | `I2C1 SDA` | [crate::Gp2I2C1Sda] | + /// | `PWM1 A` | [crate::Gp2Pwm1A] | + /// | `PIO0` | [crate::Gp2Pio0] | + /// | `PIO1` | [crate::Gp2Pio1] | + Gpio2 { + name: gpio2, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio2]. + FunctionUart, PullNone: Gp2Uart0Cts, + /// SPI Function alias for pin [crate::Pins::gpio2]. + FunctionSpi, PullNone: Gp2Spi0Sck, + /// I2C Function alias for pin [crate::Pins::gpio2]. + FunctionI2C, PullUp: Gp2I2C1Sda, + /// PWM Function alias for pin [crate::Pins::gpio2]. + FunctionPwm, PullNone: Gp2Pwm1A, + /// PIO0 Function alias for pin [crate::Pins::gpio2]. + FunctionPio0, PullNone: Gp2Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio2]. + FunctionPio1, PullNone: Gp2Pio1 + } + }, + + /// GPIO 3 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI0 TX` | [crate::Gp3Spi0Tx] | + /// | `UART0 RTS` | [crate::Gp3Uart0Rts] | + /// | `I2C1 SCL` | [crate::Gp3I2C1Scl] | + /// | `PWM1 B` | [crate::Gp3Pwm1B] | + /// | `PIO0` | [crate::Gp3Pio0] | + /// | `PIO1` | [crate::Gp3Pio1] | + Gpio3 { + name: gpio3, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio3]. + FunctionUart, PullNone: Gp3Uart0Rts, + /// SPI Function alias for pin [crate::Pins::gpio3]. + FunctionSpi, PullNone: Gp3Spi0Tx, + /// I2C Function alias for pin [crate::Pins::gpio3]. + FunctionI2C, PullUp: Gp3I2C1Scl, + /// PWM Function alias for pin [crate::Pins::gpio3]. + FunctionPwm, PullNone: Gp3Pwm1B, + /// PIO0 Function alias for pin [crate::Pins::gpio3]. + FunctionPio0, PullNone: Gp3Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio3]. + FunctionPio1, PullNone: Gp3Pio1 + } + }, + + /// GPIO 4 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI0 RX` | [crate::Gp4Spi0Rx] | + /// | `UART1 TX` | [crate::Gp4Uart1Tx] | + /// | `I2C0 SDA` | [crate::Gp4I2C0Sda] | + /// | `PWM2 A` | [crate::Gp4Pwm2A] | + /// | `PIO0` | [crate::Gp4Pio0] | + /// | `PIO1` | [crate::Gp4Pio1] | + Gpio4 { + name: gpio4, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio4]. + FunctionUart, PullNone: Gp4Uart1Tx, + /// SPI Function alias for pin [crate::Pins::gpio4]. + FunctionSpi, PullNone: Gp4Spi0Rx, + /// I2C Function alias for pin [crate::Pins::gpio4]. + FunctionI2C, PullUp: Gp4I2C0Sda, + /// PWM Function alias for pin [crate::Pins::gpio4]. + FunctionPwm, PullNone: Gp4Pwm2A, + /// PIO0 Function alias for pin [crate::Pins::gpio4]. + FunctionPio0, PullNone: Gp4Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio4]. + FunctionPio1, PullNone: Gp4Pio1 + } + }, + + /// GPIO 5 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI0 CSn` | [crate::Gp5Spi0Csn] | + /// | `UART1 RX` | [crate::Gp5Uart1Rx] | + /// | `I2C0 SCL` | [crate::Gp5I2C0Scl] | + /// | `PWM2 B` | [crate::Gp5Pwm2B] | + /// | `PIO0` | [crate::Gp5Pio0] | + /// | `PIO1` | [crate::Gp5Pio1] | + Gpio5 { + name: gpio5, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio5]. + FunctionUart, PullNone: Gp5Uart1Rx, + /// SPI Function alias for pin [crate::Pins::gpio5]. + FunctionSpi, PullNone: Gp5Spi0Csn, + /// I2C Function alias for pin [crate::Pins::gpio5]. + FunctionI2C, PullUp: Gp5I2C0Scl, + /// PWM Function alias for pin [crate::Pins::gpio5]. + FunctionPwm, PullNone: Gp5Pwm2B, + /// PIO0 Function alias for pin [crate::Pins::gpio5]. + FunctionPio0, PullNone: Gp5Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio5]. + FunctionPio1, PullNone: Gp5Pio1 + } + }, + + /// GPIO 6 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI0 SCK` | [crate::Gp6Spi0Sck] | + /// | `UART1 CTS` | [crate::Gp6Uart1Cts] | + /// | `I2C1 SDA` | [crate::Gp6I2C1Sda] | + /// | `PWM3 A` | [crate::Gp6Pwm3A] | + /// | `PIO0` | [crate::Gp6Pio0] | + /// | `PIO1` | [crate::Gp6Pio1] | + Gpio6 { + name: gpio6, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio6]. + FunctionUart, PullNone: Gp6Uart1Cts, + /// SPI Function alias for pin [crate::Pins::gpio6]. + FunctionSpi, PullNone: Gp6Spi0Sck, + /// I2C Function alias for pin [crate::Pins::gpio6]. + FunctionI2C, PullUp: Gp6I2C1Sda, + /// PWM Function alias for pin [crate::Pins::gpio6]. + FunctionPwm, PullNone: Gp6Pwm3A, + /// PIO0 Function alias for pin [crate::Pins::gpio6]. + FunctionPio0, PullNone: Gp6Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio6]. + FunctionPio1, PullNone: Gp6Pio1 + } + }, + + /// GPIO 7 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI0 TX` | [crate::Gp7Spi0Tx] | + /// | `UART1 RTS` | [crate::Gp7Uart1Rts] | + /// | `I2C1 SCL` | [crate::Gp7I2C1Scl] | + /// | `PWM3 B` | [crate::Gp7Pwm3B] | + /// | `PIO0` | [crate::Gp7Pio0] | + /// | `PIO1` | [crate::Gp7Pio1] | + Gpio7 { + name: gpio7, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio7]. + FunctionUart, PullNone: Gp7Uart1Rts, + /// SPI Function alias for pin [crate::Pins::gpio7]. + FunctionSpi, PullNone: Gp7Spi0Tx, + /// I2C Function alias for pin [crate::Pins::gpio7]. + FunctionI2C, PullUp: Gp7I2C1Scl, + /// PWM Function alias for pin [crate::Pins::gpio7]. + FunctionPwm, PullNone: Gp7Pwm3B, + /// PIO0 Function alias for pin [crate::Pins::gpio7]. + FunctionPio0, PullNone: Gp7Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio7]. + FunctionPio1, PullNone: Gp7Pio1 + } + }, + + /// GPIO 8 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI1 RX` | [crate::Gp8Spi1Rx] | + /// | `UART1 TX` | [crate::Gp8Uart1Tx] | + /// | `I2C0 SDA` | [crate::Gp8I2C0Sda] | + /// | `PWM4 A` | [crate::Gp8Pwm4A] | + /// | `PIO0` | [crate::Gp8Pio0] | + /// | `PIO1` | [crate::Gp8Pio1] | + Gpio8 { + name: gpio8, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio8]. + FunctionUart, PullNone: Gp8Uart1Tx, + /// SPI Function alias for pin [crate::Pins::gpio8]. + FunctionSpi, PullNone: Gp8Spi1Rx, + /// I2C Function alias for pin [crate::Pins::gpio8]. + FunctionI2C, PullUp: Gp8I2C0Sda, + /// PWM Function alias for pin [crate::Pins::gpio8]. + FunctionPwm, PullNone: Gp8Pwm4A, + /// PIO0 Function alias for pin [crate::Pins::gpio8]. + FunctionPio0, PullNone: Gp8Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio8]. + FunctionPio1, PullNone: Gp8Pio1 + } + }, + + /// GPIO 9 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI1 CSn` | [crate::Gp9Spi1Csn] | + /// | `UART1 RX` | [crate::Gp9Uart1Rx] | + /// | `I2C0 SCL` | [crate::Gp9I2C0Scl] | + /// | `PWM4 B` | [crate::Gp9Pwm4B] | + /// | `PIO0` | [crate::Gp9Pio0] | + /// | `PIO1` | [crate::Gp9Pio1] | + Gpio9 { + name: gpio9, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio9]. + FunctionUart, PullNone: Gp9Uart1Rx, + /// SPI Function alias for pin [crate::Pins::gpio9]. + FunctionSpi, PullNone: Gp9Spi1Csn, + /// I2C Function alias for pin [crate::Pins::gpio9]. + FunctionI2C, PullUp: Gp9I2C0Scl, + /// PWM Function alias for pin [crate::Pins::gpio9]. + FunctionPwm, PullNone: Gp9Pwm4B, + /// PIO0 Function alias for pin [crate::Pins::gpio9]. + FunctionPio0, PullNone: Gp9Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio9]. + FunctionPio1, PullNone: Gp9Pio1 + } + }, + + /// GPIO 10 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI1 SCK` | [crate::Gp10Spi1Sck] | + /// | `UART1 CTS` | [crate::Gp10Uart1Cts] | + /// | `I2C1 SDA` | [crate::Gp10I2C1Sda] | + /// | `PWM5 A` | [crate::Gp10Pwm5A] | + /// | `PIO0` | [crate::Gp10Pio0] | + /// | `PIO1` | [crate::Gp10Pio1] | + Gpio10 { + name: gpio10, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio10]. + FunctionUart, PullNone: Gp10Uart1Cts, + /// SPI Function alias for pin [crate::Pins::gpio10]. + FunctionSpi, PullNone: Gp10Spi1Sck, + /// I2C Function alias for pin [crate::Pins::gpio10]. + FunctionI2C, PullUp: Gp10I2C1Sda, + /// PWM Function alias for pin [crate::Pins::gpio10]. + FunctionPwm, PullNone: Gp10Pwm5A, + /// PIO0 Function alias for pin [crate::Pins::gpio10]. + FunctionPio0, PullNone: Gp10Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio10]. + FunctionPio1, PullNone: Gp10Pio1 + } + }, + + /// GPIO 11 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI1 TX` | [crate::Gp11Spi1Tx] | + /// | `UART1 RTS` | [crate::Gp11Uart1Rts] | + /// | `I2C1 SCL` | [crate::Gp11I2C1Scl] | + /// | `PWM5 B` | [crate::Gp11Pwm5B] | + /// | `PIO0` | [crate::Gp11Pio0] | + /// | `PIO1` | [crate::Gp11Pio1] | + Gpio11 { + name: gpio11, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio11]. + FunctionUart, PullNone: Gp11Uart1Rts, + /// SPI Function alias for pin [crate::Pins::gpio11]. + FunctionSpi, PullNone: Gp11Spi1Tx, + /// I2C Function alias for pin [crate::Pins::gpio11]. + FunctionI2C, PullUp: Gp11I2C1Scl, + /// PWM Function alias for pin [crate::Pins::gpio11]. + FunctionPwm, PullNone: Gp11Pwm5B, + /// PIO0 Function alias for pin [crate::Pins::gpio11]. + FunctionPio0, PullNone: Gp11Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio11]. + FunctionPio1, PullNone: Gp11Pio1 + } + }, + + /// GPIO 12 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI1 RX` | [crate::Gp12Spi1Rx] | + /// | `UART0 TX` | [crate::Gp12Uart0Tx] | + /// | `I2C0 SDA` | [crate::Gp12I2C0Sda] | + /// | `PWM6 A` | [crate::Gp12Pwm6A] | + /// | `PIO0` | [crate::Gp12Pio0] | + /// | `PIO1` | [crate::Gp12Pio1] | + Gpio12 { + name: gpio12, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio12]. + FunctionUart, PullNone: Gp12Uart0Tx, + /// SPI Function alias for pin [crate::Pins::gpio12]. + FunctionSpi, PullNone: Gp12Spi1Rx, + /// I2C Function alias for pin [crate::Pins::gpio12]. + FunctionI2C, PullUp: Gp12I2C0Sda, + /// PWM Function alias for pin [crate::Pins::gpio12]. + FunctionPwm, PullNone: Gp12Pwm6A, + /// PIO0 Function alias for pin [crate::Pins::gpio12]. + FunctionPio0, PullNone: Gp12Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio12]. + FunctionPio1, PullNone: Gp12Pio1 + } + }, + + /// GPIO 13 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI1 CSn` | [crate::Gp13Spi1Csn] | + /// | `UART0 RX` | [crate::Gp13Uart0Rx] | + /// | `I2C0 SCL` | [crate::Gp13I2C0Scl] | + /// | `PWM6 B` | [crate::Gp13Pwm6B] | + /// | `PIO0` | [crate::Gp13Pio0] | + /// | `PIO1` | [crate::Gp13Pio1] | + Gpio13 { + name: gpio13, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio13]. + FunctionUart, PullNone: Gp13Uart0Rx, + /// SPI Function alias for pin [crate::Pins::gpio13]. + FunctionSpi, PullNone: Gp13Spi1Csn, + /// I2C Function alias for pin [crate::Pins::gpio13]. + FunctionI2C, PullUp: Gp13I2C0Scl, + /// PWM Function alias for pin [crate::Pins::gpio13]. + FunctionPwm, PullNone: Gp13Pwm6B, + /// PIO0 Function alias for pin [crate::Pins::gpio13]. + FunctionPio0, PullNone: Gp13Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio13]. + FunctionPio1, PullNone: Gp13Pio1 + } + }, + + /// GPIO 14 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI1 SCK` | [crate::Gp14Spi1Sck] | + /// | `UART0 CTS` | [crate::Gp14Uart0Cts] | + /// | `I2C1 SDA` | [crate::Gp14I2C1Sda] | + /// | `PWM7 A` | [crate::Gp14Pwm7A] | + /// | `PIO0` | [crate::Gp14Pio0] | + /// | `PIO1` | [crate::Gp14Pio1] | + Gpio14 { + name: gpio14, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio14]. + FunctionUart, PullNone: Gp14Uart0Cts, + /// SPI Function alias for pin [crate::Pins::gpio14]. + FunctionSpi, PullNone: Gp14Spi1Sck, + /// I2C Function alias for pin [crate::Pins::gpio14]. + FunctionI2C, PullUp: Gp14I2C1Sda, + /// PWM Function alias for pin [crate::Pins::gpio14]. + FunctionPwm, PullNone: Gp14Pwm7A, + /// PIO0 Function alias for pin [crate::Pins::gpio14]. + FunctionPio0, PullNone: Gp14Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio14]. + FunctionPio1, PullNone: Gp14Pio1 + } + }, + + /// GPIO 15 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI1 TX` | [crate::Gp15Spi1Tx] | + /// | `UART0 RTS` | [crate::Gp15Uart0Rts] | + /// | `I2C1 SCL` | [crate::Gp15I2C1Scl] | + /// | `PWM7 B` | [crate::Gp15Pwm7B] | + /// | `PIO0` | [crate::Gp15Pio0] | + /// | `PIO1` | [crate::Gp15Pio1] | + Gpio15 { + name: gpio15, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio15]. + FunctionUart, PullNone: Gp15Uart0Rts, + /// SPI Function alias for pin [crate::Pins::gpio15]. + FunctionSpi, PullNone: Gp15Spi1Tx, + /// I2C Function alias for pin [crate::Pins::gpio15]. + FunctionI2C, PullUp: Gp15I2C1Scl, + /// PWM Function alias for pin [crate::Pins::gpio15]. + FunctionPwm, PullNone: Gp15Pwm7B, + /// PIO0 Function alias for pin [crate::Pins::gpio15]. + FunctionPio0, PullNone: Gp15Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio15]. + FunctionPio1, PullNone: Gp15Pio1 + } + }, + + /// GPIO 16 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI0 RX` | [crate::Gp16Spi0Rx] | + /// | `UART0 TX` | [crate::Gp16Uart0Tx] | + /// | `I2C0 SDA` | [crate::Gp16I2C0Sda] | + /// | `PWM0 A` | [crate::Gp16Pwm0A] | + /// | `PIO0` | [crate::Gp16Pio0] | + /// | `PIO1` | [crate::Gp16Pio1] | + Gpio16 { + name: gpio16, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio16]. + FunctionUart, PullNone: Gp16Uart0Tx, + /// SPI Function alias for pin [crate::Pins::gpio16]. + FunctionSpi, PullNone: Gp16Spi0Rx, + /// I2C Function alias for pin [crate::Pins::gpio16]. + FunctionI2C, PullUp: Gp16I2C0Sda, + /// PWM Function alias for pin [crate::Pins::gpio16]. + FunctionPwm, PullNone: Gp16Pwm0A, + /// PIO0 Function alias for pin [crate::Pins::gpio16]. + FunctionPio0, PullNone: Gp16Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio16]. + FunctionPio1, PullNone: Gp16Pio1 + } + }, + + /// GPIO 17 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI0 CSn` | [crate::Gp17Spi0Csn] | + /// | `UART0 RX` | [crate::Gp17Uart0Rx] | + /// | `I2C0 SCL` | [crate::Gp17I2C0Scl] | + /// | `PWM0 B` | [crate::Gp17Pwm0B] | + /// | `PIO0` | [crate::Gp17Pio0] | + /// | `PIO1` | [crate::Gp17Pio1] | + Gpio17 { + name: gpio17, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio17]. + FunctionUart, PullNone: Gp17Uart0Rx, + /// SPI Function alias for pin [crate::Pins::gpio17]. + FunctionSpi, PullNone: Gp17Spi0Csn, + /// I2C Function alias for pin [crate::Pins::gpio17]. + FunctionI2C, PullUp: Gp17I2C0Scl, + /// PWM Function alias for pin [crate::Pins::gpio17]. + FunctionPwm, PullNone: Gp17Pwm0B, + /// PIO0 Function alias for pin [crate::Pins::gpio17]. + FunctionPio0, PullNone: Gp17Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio17]. + FunctionPio1, PullNone: Gp17Pio1 + } + }, + + /// GPIO 18 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI0 SCK` | [crate::Gp18Spi0Sck] | + /// | `UART0 CTS` | [crate::Gp18Uart0Cts] | + /// | `I2C1 SDA` | [crate::Gp18I2C1Sda] | + /// | `PWM1 A` | [crate::Gp18Pwm1A] | + /// | `PIO0` | [crate::Gp18Pio0] | + /// | `PIO1` | [crate::Gp18Pio1] | + Gpio18 { + name: gpio18, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio18]. + FunctionUart, PullNone: Gp18Uart0Cts, + /// SPI Function alias for pin [crate::Pins::gpio18]. + FunctionSpi, PullNone: Gp18Spi0Sck, + /// I2C Function alias for pin [crate::Pins::gpio18]. + FunctionI2C, PullUp: Gp18I2C1Sda, + /// PWM Function alias for pin [crate::Pins::gpio18]. + FunctionPwm, PullNone: Gp18Pwm1A, + /// PIO0 Function alias for pin [crate::Pins::gpio18]. + FunctionPio0, PullNone: Gp18Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio18]. + FunctionPio1, PullNone: Gp18Pio1 + } + }, + + /// GPIO 19 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI0 TX` | [crate::Gp19Spi0Tx] | + /// | `UART0 RTS` | [crate::Gp19Uart0Rts] | + /// | `I2C1 SCL` | [crate::Gp19I2C1Scl] | + /// | `PWM1 B` | [crate::Gp19Pwm1B] | + /// | `PIO0` | [crate::Gp19Pio0] | + /// | `PIO1` | [crate::Gp19Pio1] | + Gpio19 { + name: gpio19, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio19]. + FunctionUart, PullNone: Gp19Uart0Rts, + /// SPI Function alias for pin [crate::Pins::gpio19]. + FunctionSpi, PullNone: Gp19Spi0Tx, + /// I2C Function alias for pin [crate::Pins::gpio19]. + FunctionI2C, PullUp: Gp19I2C1Scl, + /// PWM Function alias for pin [crate::Pins::gpio19]. + FunctionPwm, PullNone: Gp19Pwm1B, + /// PIO0 Function alias for pin [crate::Pins::gpio19]. + FunctionPio0, PullNone: Gp19Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio19]. + FunctionPio1, PullNone: Gp19Pio1 + } + }, + + /// GPIO 20 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI0 RX` | [crate::Gp20Spi0Rx] | + /// | `UART1 TX` | [crate::Gp20Uart1Tx] | + /// | `I2C0 SDA` | [crate::Gp20I2C0Sda] | + /// | `PWM2 A` | [crate::Gp20Pwm2A] | + /// | `PIO0` | [crate::Gp20Pio0] | + /// | `PIO1` | [crate::Gp20Pio1] | + Gpio20 { + name: gpio20, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio20]. + FunctionUart, PullNone: Gp20Uart1Tx, + /// SPI Function alias for pin [crate::Pins::gpio20]. + FunctionSpi, PullNone: Gp20Spi0Rx, + /// I2C Function alias for pin [crate::Pins::gpio20]. + FunctionI2C, PullUp: Gp20I2C0Sda, + /// PWM Function alias for pin [crate::Pins::gpio20]. + FunctionPwm, PullNone: Gp20Pwm2A, + /// PIO0 Function alias for pin [crate::Pins::gpio20]. + FunctionPio0, PullNone: Gp20Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio20]. + FunctionPio1, PullNone: Gp20Pio1 + } + }, + + /// GPIO 21 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI0 CSn` | [crate::Gp21Spi0Csn] | + /// | `UART1 RX` | [crate::Gp21Uart1Rx] | + /// | `I2C0 SCL` | [crate::Gp21I2C0Scl] | + /// | `PWM2 B` | [crate::Gp21Pwm2B] | + /// | `PIO0` | [crate::Gp21Pio0] | + /// | `PIO1` | [crate::Gp21Pio1] | + Gpio21 { + name: gpio21, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio21]. + FunctionUart, PullNone: Gp21Uart1Rx, + /// SPI Function alias for pin [crate::Pins::gpio21]. + FunctionSpi, PullNone: Gp21Spi0Csn, + /// I2C Function alias for pin [crate::Pins::gpio21]. + FunctionI2C, PullUp: Gp21I2C0Scl, + /// PWM Function alias for pin [crate::Pins::gpio21]. + FunctionPwm, PullNone: Gp21Pwm2B, + /// PIO0 Function alias for pin [crate::Pins::gpio21]. + FunctionPio0, PullNone: Gp21Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio21]. + FunctionPio1, PullNone: Gp21Pio1 + } + }, + + /// GPIO 22 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI0 SCK` | [crate::Gp22Spi0Sck] | + /// | `UART1 CTS` | [crate::Gp22Uart1Cts] | + /// | `I2C1 SDA` | [crate::Gp22I2C1Sda] | + /// | `PWM3 A` | [crate::Gp22Pwm3A] | + /// | `PIO0` | [crate::Gp22Pio0] | + /// | `PIO1` | [crate::Gp22Pio1] | + Gpio22 { + name: gpio22, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio22]. + FunctionUart, PullNone: Gp22Uart1Cts, + /// SPI Function alias for pin [crate::Pins::gpio22]. + FunctionSpi, PullNone: Gp22Spi0Sck, + /// I2C Function alias for pin [crate::Pins::gpio22]. + FunctionI2C, PullUp: Gp22I2C1Sda, + /// PWM Function alias for pin [crate::Pins::gpio22]. + FunctionPwm, PullNone: Gp22Pwm3A, + /// PIO0 Function alias for pin [crate::Pins::gpio22]. + FunctionPio0, PullNone: Gp22Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio22]. + FunctionPio1, PullNone: Gp22Pio1 + } + }, + + /// GPIO 23 is connected to b_power_save of the Raspberry Pi Pico board. + Gpio23 { + name: b_power_save, + }, + + /// GPIO 24 is connected to vbus_detect of the Raspberry Pi Pico board. + Gpio24 { + name: vbus_detect, + }, + + /// GPIO 25 is connected to led of the Raspberry Pi Pico board. + Gpio25 { + name: led, + }, + + /// GPIO 26 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI1 SCK` | [crate::Gp26Spi1Sck] | + /// | `UART1 CTS` | [crate::Gp26Uart1Cts] | + /// | `I2C1 SDA` | [crate::Gp26I2C1Sda] | + /// | `PWM5 A` | [crate::Gp26Pwm5A] | + /// | `PIO0` | [crate::Gp26Pio0] | + /// | `PIO1` | [crate::Gp26Pio1] | + Gpio26 { + name: gpio26, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio26]. + FunctionUart, PullNone: Gp26Uart1Cts, + /// SPI Function alias for pin [crate::Pins::gpio26]. + FunctionSpi, PullNone: Gp26Spi1Sck, + /// I2C Function alias for pin [crate::Pins::gpio26]. + FunctionI2C, PullUp: Gp26I2C1Sda, + /// PWM Function alias for pin [crate::Pins::gpio26]. + FunctionPwm, PullNone: Gp26Pwm5A, + /// PIO0 Function alias for pin [crate::Pins::gpio26]. + FunctionPio0, PullNone: Gp26Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio26]. + FunctionPio1, PullNone: Gp26Pio1 + } + }, + + /// GPIO 27 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI1 TX` | [crate::Gp27Spi1Tx] | + /// | `UART1 RTS` | [crate::Gp27Uart1Rts] | + /// | `I2C1 SCL` | [crate::Gp27I2C1Scl] | + /// | `PWM5 B` | [crate::Gp27Pwm5B] | + /// | `PIO0` | [crate::Gp27Pio0] | + /// | `PIO1` | [crate::Gp27Pio1] | + Gpio27 { + name: gpio27, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio27]. + FunctionUart, PullNone: Gp27Uart1Rts, + /// SPI Function alias for pin [crate::Pins::gpio27]. + FunctionSpi, PullNone: Gp27Spi1Tx, + /// I2C Function alias for pin [crate::Pins::gpio27]. + FunctionI2C, PullUp: Gp27I2C1Scl, + /// PWM Function alias for pin [crate::Pins::gpio27]. + FunctionPwm, PullNone: Gp27Pwm5B, + /// PIO0 Function alias for pin [crate::Pins::gpio27]. + FunctionPio0, PullNone: Gp27Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio27]. + FunctionPio1, PullNone: Gp27Pio1 + } + }, + + /// GPIO 28 supports following functions: + /// + /// | Function | Alias with applied function | + /// |--------------|-----------------------------| + /// | `SPI1 RX` | [crate::Gp28Spi1Rx] | + /// | `UART0 TX` | [crate::Gp28Uart0Tx] | + /// | `I2C0 SDA` | [crate::Gp28I2C0Sda] | + /// | `PWM6 A` | [crate::Gp28Pwm6A] | + /// | `PIO0` | [crate::Gp28Pio0] | + /// | `PIO1` | [crate::Gp28Pio1] | + Gpio28 { + name: gpio28, + aliases: { + /// UART Function alias for pin [crate::Pins::gpio28]. + FunctionUart, PullNone: Gp28Uart0Tx, + /// SPI Function alias for pin [crate::Pins::gpio28]. + FunctionSpi, PullNone: Gp28Spi1Rx, + /// I2C Function alias for pin [crate::Pins::gpio28]. + FunctionI2C, PullUp: Gp28I2C0Sda, + /// PWM Function alias for pin [crate::Pins::gpio28]. + FunctionPwm, PullNone: Gp28Pwm6A, + /// PIO0 Function alias for pin [crate::Pins::gpio28]. + FunctionPio0, PullNone: Gp28Pio0, + /// PIO1 Function alias for pin [crate::Pins::gpio28]. + FunctionPio1, PullNone: Gp28Pio1 + } + }, + + /// GPIO 29 is connected to voltage_monitor of the Raspberry Pi Pico board. + Gpio29 { + name: voltage_monitor, + }, +); + +pub const XOSC_CRYSTAL_FREQ: u32 = 12_000_000;