From 121b467fb9ca40cd1ba9af5e1ebf806ad1b5a0d3 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 16 Apr 2025 14:35:57 +0200 Subject: [PATCH] move to updated API --- bootloader/Cargo.toml | 2 + bootloader/src/main.rs | 10 +- examples/embassy/Cargo.toml | 2 +- examples/embassy/src/bin/async-gpio.rs | 47 ++-- examples/embassy/src/bin/async-uart-rx.rs | 39 +-- examples/embassy/src/bin/async-uart-tx.rs | 26 +- examples/embassy/src/main.rs | 17 +- examples/rtic/Cargo.toml | 4 +- examples/rtic/src/bin/blinky-button-rtic.rs | 30 +-- examples/rtic/src/bin/uart-echo-rtic.rs | 23 +- examples/rtic/src/main.rs | 20 +- examples/simple/Cargo.toml | 2 + examples/simple/examples/blinky.rs | 45 ++-- examples/simple/examples/cascade.rs | 51 +--- examples/simple/examples/pwm.rs | 27 +- examples/simple/examples/spi.rs | 209 +++++---------- examples/simple/examples/timer-ticks.rs | 24 +- examples/simple/examples/uart.rs | 19 +- flashloader/Cargo.toml | 1 + flashloader/src/main.rs | 18 +- va108xx-embassy/Cargo.toml | 2 +- va108xx-embassy/src/lib.rs | 58 ++-- va108xx-hal/src/clock.rs | 19 +- va108xx-hal/src/i2c.rs | 7 +- va108xx-hal/src/pins.rs | 21 +- va108xx-hal/src/pwm.rs | 19 +- va108xx-hal/src/spi/mod.rs | 202 ++++++-------- va108xx-hal/src/spi/pins.rs | 27 +- va108xx-hal/src/sysconfig.rs | 28 +- va108xx-hal/src/timer.rs | 79 ++---- va108xx-hal/src/uart/mod.rs | 13 +- va108xx-hal/src/uart/rx_asynch.rs | 4 +- vorago-reb1/Cargo.toml | 5 +- vorago-reb1/examples/adt75-temp-sensor.rs | 8 +- vorago-reb1/examples/adxl343-accelerometer.rs | 30 +-- vorago-reb1/examples/blinky-button-irq.rs | 30 +-- vorago-reb1/examples/blinky-leds.rs | 30 ++- vorago-reb1/src/button.rs | 10 +- vorago-reb1/src/leds.rs | 38 +-- vorago-reb1/src/m95m01.rs | 46 ++-- vorago-reb1/src/max11619.rs | 7 +- vorago-reb1/src/temp_sensor.rs | 7 +- vorago-shared-periphs/src/gpio/asynch.rs | 5 +- vorago-shared-periphs/src/gpio/ll.rs | 253 +++++++++++------- vorago-shared-periphs/src/gpio/mod.rs | 59 +++- vorago-shared-periphs/src/ioconfig/mod.rs | 2 + vorago-shared-periphs/src/ioconfig/regs.rs | 86 +----- vorago-shared-periphs/src/pins.rs | 0 vorago-shared-periphs/src/sysconfig.rs | 26 ++ 49 files changed, 751 insertions(+), 986 deletions(-) create mode 100644 vorago-shared-periphs/src/pins.rs diff --git a/bootloader/Cargo.toml b/bootloader/Cargo.toml index 1aaf734..13ab933 100644 --- a/bootloader/Cargo.toml +++ b/bootloader/Cargo.toml @@ -16,9 +16,11 @@ static_assertions = "1" [dependencies.va108xx-hal] version = "0.11" +path = "../va108xx-hal" [dependencies.vorago-reb1] version = "0.8" +path = "../vorago-reb1" [features] default = [] diff --git a/bootloader/src/main.rs b/bootloader/src/main.rs index dd8a028..b55ef6f 100644 --- a/bootloader/src/main.rs +++ b/bootloader/src/main.rs @@ -104,11 +104,11 @@ fn main() -> ! { rtt_init_print!(); rprintln!("-- VA108xx bootloader --"); } - let mut dp = pac::Peripherals::take().unwrap(); + let dp = pac::Peripherals::take().unwrap(); let cp = cortex_m::Peripherals::take().unwrap(); - let mut timer = CountdownTimer::new(&mut dp.sysconfig, CLOCK_FREQ, dp.tim0); + let mut timer = CountdownTimer::new(CLOCK_FREQ, dp.tim0); - let mut nvm = M95M01::new(&mut dp.sysconfig, CLOCK_FREQ, dp.spic); + let mut nvm = M95M01::new(CLOCK_FREQ, dp.spic); if FLASH_SELF { let mut first_four_bytes: [u8; 4] = [0; 4]; @@ -186,7 +186,7 @@ fn check_own_crc( sysconfig: &pac::Sysconfig, cp: &cortex_m::Peripherals, nvm: &mut NvmWrapper, - timer: &mut CountdownTimer, + timer: &mut CountdownTimer, ) { let crc_exp = unsafe { (BOOTLOADER_CRC_ADDR as *const u16).read_unaligned().to_be() }; // I'd prefer to use [core::slice::from_raw_parts], but that is problematic @@ -276,7 +276,7 @@ fn boot_app( syscfg: &pac::Sysconfig, cp: &cortex_m::Peripherals, app_sel: AppSel, - timer: &mut CountdownTimer, + timer: &mut CountdownTimer, ) -> ! { if DEBUG_PRINTOUTS && RTT_PRINTOUT { rprintln!("booting app {:?}", app_sel); diff --git a/examples/embassy/Cargo.toml b/examples/embassy/Cargo.toml index 039e18a..6356d17 100644 --- a/examples/embassy/Cargo.toml +++ b/examples/embassy/Cargo.toml @@ -29,7 +29,7 @@ embassy-executor = { version = "0.7", features = [ "executor-interrupt" ]} -va108xx-hal = { version = "0.11", features = ["defmt"] } +va108xx-hal = { version = "0.11", path = "../../va108xx-hal", features = ["defmt"] } va108xx-embassy = { version = "0.2" } [features] diff --git a/examples/embassy/src/bin/async-gpio.rs b/examples/embassy/src/bin/async-gpio.rs index e06f774..7c51bdb 100644 --- a/examples/embassy/src/bin/async-gpio.rs +++ b/examples/embassy/src/bin/async-gpio.rs @@ -12,11 +12,10 @@ use embassy_sync::channel::{Receiver, Sender}; use embassy_sync::{blocking_mutex::raw::ThreadModeRawMutex, channel::Channel}; use embassy_time::{Duration, Instant, Timer}; use embedded_hal_async::digital::Wait; -use va108xx_hal::gpio::{ - on_interrupt_for_async_gpio_for_port, InputDynPinAsync, InputPinAsync, PinsB, Port, -}; +use va108xx_hal::gpio::asynch::{on_interrupt_for_async_gpio_for_port, InputPinAsync}; +use va108xx_hal::gpio::{Input, Output, PinState, Port}; +use va108xx_hal::pins::{PinsA, PinsB}; use va108xx_hal::{ - gpio::{DynPin, PinsA}, pac::{self, interrupt}, prelude::*, }; @@ -71,30 +70,28 @@ async fn main(spawner: Spawner) { dp.tim22, ); - let porta = PinsA::new(&mut dp.sysconfig, dp.porta); - let portb = PinsB::new(&mut dp.sysconfig, dp.portb); - let mut led0 = porta.pa10.into_readable_push_pull_output(); - let out_pa0 = porta.pa0.into_readable_push_pull_output(); - let in_pa1 = porta.pa1.into_floating_input(); - let out_pb22 = portb.pb22.into_readable_push_pull_output(); - let in_pb23 = portb.pb23.into_floating_input(); + let porta = PinsA::new(dp.porta); + let portb = PinsB::new(dp.portb); + let mut led0 = Output::new(porta.pa10, PinState::Low); + let out_pa0 = Output::new(porta.pa0, PinState::Low); + let in_pa1 = Input::new_floating(porta.pa1); + let out_pb22 = Output::new(portb.pb22, PinState::Low); + let in_pb23 = Input::new_floating(portb.pb23); let in_pa1_async = InputPinAsync::new(in_pa1, pac::Interrupt::OC10); - let out_pa0_dyn = out_pa0.downgrade(); - let in_pb23_async = InputDynPinAsync::new(in_pb23.downgrade(), PB22_TO_PB23_IRQ).unwrap(); - let out_pb22_dyn = out_pb22.downgrade(); + let in_pb23_async = InputPinAsync::new(in_pb23, PB22_TO_PB23_IRQ); spawner .spawn(output_task( "PA0 to PA1", - out_pa0_dyn, + out_pa0, CHANNEL_PA0_PA1.receiver(), )) .unwrap(); spawner .spawn(output_task( "PB22 to PB23", - out_pb22_dyn, + out_pb22, CHANNEL_PB22_TO_PB23.receiver(), )) .unwrap(); @@ -207,7 +204,7 @@ async fn check_pin_to_pin_async_ops( #[embassy_executor::task(pool_size = 2)] async fn output_task( ctx: &'static str, - mut out: DynPin, + mut out: Output, receiver: Receiver<'static, ThreadModeRawMutex, GpioCmd, 3>, ) { loop { @@ -216,25 +213,25 @@ async fn output_task( match next_cmd.cmd_type { GpioCmdType::SetHigh => { defmt::info!("{}: Set output high", ctx); - out.set_high().unwrap(); + out.set_high(); } GpioCmdType::SetLow => { defmt::info!("{}: Set output low", ctx); - out.set_low().unwrap(); + out.set_low(); } GpioCmdType::RisingEdge => { defmt::info!("{}: Rising edge", ctx); - if !out.is_low().unwrap() { - out.set_low().unwrap(); + if !out.is_set_high() { + out.set_low(); } - out.set_high().unwrap(); + out.set_high(); } GpioCmdType::FallingEdge => { defmt::info!("{}: Falling edge", ctx); - if !out.is_high().unwrap() { - out.set_high().unwrap(); + if !out.is_set_high() { + out.set_high(); } - out.set_low().unwrap(); + out.set_low(); } } } diff --git a/examples/embassy/src/bin/async-uart-rx.rs b/examples/embassy/src/bin/async-uart-rx.rs index 33a974d..70a8f58 100644 --- a/examples/embassy/src/bin/async-uart-rx.rs +++ b/examples/embassy/src/bin/async-uart-rx.rs @@ -24,13 +24,14 @@ use embedded_io::Write; use embedded_io_async::Read; use heapless::spsc::{Consumer, Producer, Queue}; use va108xx_hal::{ - gpio::PinsA, + gpio::{Output, PinState}, pac::{self, interrupt}, + pins::PinsA, prelude::*, uart::{ self, on_interrupt_rx_overwriting, rx_asynch::{on_interrupt_rx, RxAsync}, - Bank, RxAsyncOverwriting, Tx, + RxAsyncOverwriting, Tx, UartId, }, InterruptConfig, }; @@ -62,34 +63,34 @@ async fn main(spawner: Spawner) { dp.tim22, ); - let porta = PinsA::new(&mut dp.sysconfig, dp.porta); - let mut led0 = porta.pa10.into_readable_push_pull_output(); - let mut led1 = porta.pa7.into_readable_push_pull_output(); - let mut led2 = porta.pa6.into_readable_push_pull_output(); + let porta = PinsA::new(dp.porta); + let mut led0 = Output::new(porta.pa10, PinState::Low); + let mut led1 = Output::new(porta.pa7, PinState::Low); + let mut led2 = Output::new(porta.pa6, PinState::Low); - let tx_uart_a = porta.pa9.into_funsel_2(); - let rx_uart_a = porta.pa8.into_funsel_2(); + let tx_uart_a = porta.pa9; + let rx_uart_a = porta.pa8; let uarta = uart::Uart::new_with_interrupt( - &mut dp.sysconfig, 50.MHz(), dp.uarta, (tx_uart_a, rx_uart_a), - 115200.Hz(), + 115200.Hz().into(), InterruptConfig::new(pac::Interrupt::OC2, true, true), - ); + ) + .unwrap(); - let tx_uart_b = porta.pa3.into_funsel_2(); - let rx_uart_b = porta.pa2.into_funsel_2(); + let tx_uart_b = porta.pa3; + let rx_uart_b = porta.pa2; let uartb = uart::Uart::new_with_interrupt( - &mut dp.sysconfig, 50.MHz(), dp.uartb, (tx_uart_b, rx_uart_b), - 115200.Hz(), + 115200.Hz().into(), InterruptConfig::new(pac::Interrupt::OC3, true, true), - ); + ) + .unwrap(); let (mut tx_uart_a, rx_uart_a) = uarta.split(); let (tx_uart_b, rx_uart_b) = uartb.split(); let (prod_uart_a, cons_uart_a) = QUEUE_UART_A.take().split(); @@ -123,7 +124,7 @@ async fn main(spawner: Spawner) { } #[embassy_executor::task] -async fn uart_b_task(mut async_rx: RxAsyncOverwriting, mut tx: Tx) { +async fn uart_b_task(mut async_rx: RxAsyncOverwriting<256>, mut tx: Tx) { let mut buf = [0u8; 256]; loop { defmt::info!("Current time UART B: {}", Instant::now().as_secs()); @@ -144,7 +145,7 @@ async fn uart_b_task(mut async_rx: RxAsyncOverwriting, mut tx: fn OC2() { let mut prod = critical_section::with(|cs| PRODUCER_UART_A.borrow(cs).borrow_mut().take().unwrap()); - let errors = on_interrupt_rx(Bank::A, &mut prod); + let errors = on_interrupt_rx(UartId::A, &mut prod); critical_section::with(|cs| *PRODUCER_UART_A.borrow(cs).borrow_mut() = Some(prod)); // In a production app, we could use a channel to send the errors to the main task. if let Err(errors) = errors { @@ -157,7 +158,7 @@ fn OC2() { fn OC3() { let mut prod = critical_section::with(|cs| PRODUCER_UART_B.borrow(cs).borrow_mut().take().unwrap()); - let errors = on_interrupt_rx_overwriting(Bank::B, &mut prod, &CONSUMER_UART_B); + let errors = on_interrupt_rx_overwriting(UartId::B, &mut prod, &CONSUMER_UART_B); critical_section::with(|cs| *PRODUCER_UART_B.borrow(cs).borrow_mut() = Some(prod)); // In a production app, we could use a channel to send the errors to the main task. if let Err(errors) = errors { diff --git a/examples/embassy/src/bin/async-uart-tx.rs b/examples/embassy/src/bin/async-uart-tx.rs index 29ee434..2f47b22 100644 --- a/examples/embassy/src/bin/async-uart-tx.rs +++ b/examples/embassy/src/bin/async-uart-tx.rs @@ -17,10 +17,11 @@ use embassy_executor::Spawner; use embassy_time::{Duration, Instant, Ticker}; use embedded_io_async::Write; use va108xx_hal::{ - gpio::PinsA, + gpio::{Output, PinState}, pac::{self, interrupt}, + pins::PinsA, prelude::*, - uart::{self, on_interrupt_tx, Bank, TxAsync}, + uart::{self, on_interrupt_tx, TxAsync, UartId}, InterruptConfig, }; @@ -49,22 +50,23 @@ async fn main(_spawner: Spawner) { dp.tim22, ); - let porta = PinsA::new(&mut dp.sysconfig, dp.porta); - let mut led0 = porta.pa10.into_readable_push_pull_output(); - let mut led1 = porta.pa7.into_readable_push_pull_output(); - let mut led2 = porta.pa6.into_readable_push_pull_output(); + let porta = PinsA::new(dp.porta); - let tx = porta.pa9.into_funsel_2(); - let rx = porta.pa8.into_funsel_2(); + let mut led0 = Output::new(porta.pa10, PinState::Low); + let mut led1 = Output::new(porta.pa7, PinState::Low); + let mut led2 = Output::new(porta.pa6, PinState::Low); + + let tx = porta.pa9; + let rx = porta.pa8; let uarta = uart::Uart::new_with_interrupt( - &mut dp.sysconfig, 50.MHz(), dp.uarta, (tx, rx), - 115200.Hz(), + 115200.Hz().into(), InterruptConfig::new(pac::Interrupt::OC2, true, true), - ); + ) + .unwrap(); let (tx, _rx) = uarta.split(); let mut async_tx = TxAsync::new(tx); let mut ticker = Ticker::every(Duration::from_secs(1)); @@ -89,5 +91,5 @@ async fn main(_spawner: Spawner) { #[interrupt] #[allow(non_snake_case)] fn OC2() { - on_interrupt_tx(Bank::A); + on_interrupt_tx(UartId::A); } diff --git a/examples/embassy/src/main.rs b/examples/embassy/src/main.rs index 35e0411..7e38a1c 100644 --- a/examples/embassy/src/main.rs +++ b/examples/embassy/src/main.rs @@ -12,7 +12,12 @@ cfg_if::cfg_if! { } } -use va108xx_hal::{gpio::PinsA, pac, prelude::*}; +use va108xx_hal::{ + gpio::{Output, PinState}, + pac, + pins::PinsA, + prelude::*, +}; const SYSCLK_FREQ: Hertz = Hertz::from_raw(50_000_000); @@ -35,8 +40,6 @@ async fn main(_spawner: Spawner) { ); } else { va108xx_embassy::init_with_custom_irqs( - &mut dp.sysconfig, - &dp.irqsel, SYSCLK_FREQ, dp.tim23, dp.tim22, @@ -46,10 +49,10 @@ async fn main(_spawner: Spawner) { } } - let porta = PinsA::new(&mut dp.sysconfig, dp.porta); - let mut led0 = porta.pa10.into_readable_push_pull_output(); - let mut led1 = porta.pa7.into_readable_push_pull_output(); - let mut led2 = porta.pa6.into_readable_push_pull_output(); + let porta = PinsA::new(dp.porta); + let mut led0 = Output::new(porta.pa10, PinState::Low); + let mut led1 = Output::new(porta.pa7, PinState::Low); + let mut led2 = Output::new(porta.pa6, PinState::Low); let mut ticker = Ticker::every(Duration::from_secs(1)); loop { ticker.next().await; diff --git a/examples/rtic/Cargo.toml b/examples/rtic/Cargo.toml index 30ec487..d4698e3 100644 --- a/examples/rtic/Cargo.toml +++ b/examples/rtic/Cargo.toml @@ -22,5 +22,5 @@ rtic-sync = { version = "1.3", features = ["defmt-03"] } once_cell = {version = "1", default-features = false, features = ["critical-section"]} ringbuf = { version = "0.4.7", default-features = false, features = ["portable-atomic"] } -va108xx-hal = { version = "0.11" } -vorago-reb1 = { version = "0.8" } +va108xx-hal = { version = "0.11", path = "../../va108xx-hal" } +vorago-reb1 = { version = "0.8", path = "../../vorago-reb1" } diff --git a/examples/rtic/src/bin/blinky-button-rtic.rs b/examples/rtic/src/bin/blinky-button-rtic.rs index bba2d4c..da4dc8d 100644 --- a/examples/rtic/src/bin/blinky-button-rtic.rs +++ b/examples/rtic/src/bin/blinky-button-rtic.rs @@ -9,10 +9,10 @@ mod app { use rtt_target::{rprintln, rtt_init_default, set_print_channel}; use va108xx_hal::{ clock::{set_clk_div_register, FilterClkSel}, - gpio::{FilterType, InterruptEdge, PinsA}, + gpio::{FilterType, InterruptEdge}, pac, - prelude::*, - timer::{default_ms_irq_handler, set_up_ms_tick, InterruptConfig}, + pins::PinsA, + timer::InterruptConfig, }; use vorago_reb1::button::Button; use vorago_reb1::leds::Leds; @@ -61,39 +61,28 @@ mod app { rprintln!("Using {:?} mode", mode); let mut dp = cx.device; - let pinsa = PinsA::new(&mut dp.sysconfig, dp.porta); + let pinsa = PinsA::new(dp.porta); let edge_irq = match mode { PressMode::Toggle => InterruptEdge::HighToLow, PressMode::Keep => InterruptEdge::BothEdges, }; // Configure an edge interrupt on the button and route it to interrupt vector 15 - let mut button = Button::new(pinsa.pa11.into_floating_input()); + let mut button = Button::new(pinsa.pa11); if mode == PressMode::Toggle { // This filter debounces the switch for edge based interrupts - button.configure_filter_type(FilterType::FilterFourClockCycles, FilterClkSel::Clk1); + button.configure_filter_type(FilterType::FilterFourCycles, FilterClkSel::Clk1); set_clk_div_register(&mut dp.sysconfig, FilterClkSel::Clk1, 50_000); } button.configure_and_enable_edge_interrupt( edge_irq, InterruptConfig::new(pac::interrupt::OC15, true, true), ); - let mut leds = Leds::new( - pinsa.pa10.into_push_pull_output(), - pinsa.pa7.into_push_pull_output(), - pinsa.pa6.into_push_pull_output(), - ); + let mut leds = Leds::new(pinsa.pa10, pinsa.pa7, pinsa.pa6); for led in leds.iter_mut() { led.off(); } - set_up_ms_tick( - InterruptConfig::new(pac::Interrupt::OC0, true, true), - &mut dp.sysconfig, - Some(&mut dp.irqsel), - 50.MHz(), - dp.tim0, - ); (Shared {}, Local { leds, button, mode }) } @@ -119,11 +108,6 @@ mod app { } } - #[task(binds = OC0)] - fn ms_tick(_cx: ms_tick::Context) { - default_ms_irq_handler(); - } - fn prompt_mode(mut down_channel: rtt_target::DownChannel) -> PressMode { rprintln!("Using prompt mode"); rprintln!("Please enter the mode [0: Toggle, 1: Keep]"); diff --git a/examples/rtic/src/bin/uart-echo-rtic.rs b/examples/rtic/src/bin/uart-echo-rtic.rs index 296e66e..344d6d5 100644 --- a/examples/rtic/src/bin/uart-echo-rtic.rs +++ b/examples/rtic/src/bin/uart-echo-rtic.rs @@ -20,17 +20,13 @@ mod app { use rtic_monotonics::Monotonic; use rtt_target::{rprintln, rtt_init_print}; use va108xx_hal::{ - gpio::PinsA, - pac, - prelude::*, - uart::{self, RxWithInterrupt, Tx}, - InterruptConfig, + pac, pins::PinsA, prelude::*, uart::{self, RxWithInterrupt, Tx}, InterruptConfig }; #[local] struct Local { - rx: RxWithInterrupt, - tx: Tx, + rx: RxWithInterrupt, + tx: Tx, } #[shared] @@ -47,19 +43,18 @@ mod app { Mono::start(cx.core.SYST, SYSCLK_FREQ.raw()); - let mut dp = cx.device; - let gpioa = PinsA::new(&mut dp.sysconfig, dp.porta); - let tx = gpioa.pa9.into_funsel_2(); - let rx = gpioa.pa8.into_funsel_2(); + let dp = cx.device; + let gpioa = PinsA::new(dp.porta); + let tx = gpioa.pa9; + let rx = gpioa.pa8; let irq_uart = uart::Uart::new_with_interrupt( - &mut dp.sysconfig, SYSCLK_FREQ, dp.uarta, (tx, rx), - 115200.Hz(), + 115200.Hz().into(), InterruptConfig::new(pac::Interrupt::OC3, true, true), - ); + ).unwrap(); let (tx, rx) = irq_uart.split(); let mut rx = rx.into_rx_with_irq(); diff --git a/examples/rtic/src/main.rs b/examples/rtic/src/main.rs index ad6ccd9..2986567 100644 --- a/examples/rtic/src/main.rs +++ b/examples/rtic/src/main.rs @@ -11,15 +11,15 @@ mod app { use rtic_monotonics::Monotonic; use rtt_target::{rprintln, rtt_init_print}; use va108xx_hal::{ - gpio::{OutputReadablePushPull, Pin, PinsA, PA10, PA6, PA7}, - pac, + gpio::{Output, PinState}, + pac, pins::PinsA, }; #[local] struct Local { - led0: Pin, - led1: Pin, - led2: Pin, + led0: Output, + led1: Output, + led2: Output, } #[shared] @@ -28,16 +28,16 @@ mod app { rtic_monotonics::systick_monotonic!(Mono, 1_000); #[init] - fn init(mut cx: init::Context) -> (Shared, Local) { + fn init(cx: init::Context) -> (Shared, Local) { rtt_init_print!(); rprintln!("-- Vorago VA108xx RTIC template --"); Mono::start(cx.core.SYST, SYSCLK_FREQ.raw()); - let porta = PinsA::new(&mut cx.device.sysconfig, cx.device.porta); - let led0 = porta.pa10.into_readable_push_pull_output(); - let led1 = porta.pa7.into_readable_push_pull_output(); - let led2 = porta.pa6.into_readable_push_pull_output(); + let porta = PinsA::new(cx.device.porta); + let led0 = Output::new(porta.pa10, PinState::Low); + let led1 = Output::new(porta.pa7, PinState::Low); + let led2 = Output::new(porta.pa6, PinState::Low); blinky::spawn().ok(); (Shared {}, Local { led0, led1, led2 }) } diff --git a/examples/simple/Cargo.toml b/examples/simple/Cargo.toml index 158cbff..83a19b7 100644 --- a/examples/simple/Cargo.toml +++ b/examples/simple/Cargo.toml @@ -17,7 +17,9 @@ cortex-m-semihosting = "0.5.0" [dependencies.va108xx-hal] version = "0.11" +path = "../../va108xx-hal" features = ["defmt"] [dependencies.vorago-reb1] +path = "../../vorago-reb1" version = "0.8" diff --git a/examples/simple/examples/blinky.rs b/examples/simple/examples/blinky.rs index bcdfe0c..1d30b82 100644 --- a/examples/simple/examples/blinky.rs +++ b/examples/simple/examples/blinky.rs @@ -10,52 +10,37 @@ use cortex_m_rt::entry; use embedded_hal::delay::DelayNs; use panic_halt as _; use va108xx_hal::{ - gpio::PinsA, - pac::{self, interrupt}, + gpio::{Output, PinState}, + pac::{self}, + pins::PinsA, prelude::*, - timer::DelayMs, - timer::{default_ms_irq_handler, set_up_ms_tick, CountdownTimer}, - InterruptConfig, + timer::CountdownTimer, }; #[entry] fn main() -> ! { - let mut dp = pac::Peripherals::take().unwrap(); - let mut delay_ms = DelayMs::new(set_up_ms_tick( - InterruptConfig::new(interrupt::OC0, true, true), - &mut dp.sysconfig, - Some(&mut dp.irqsel), - 50.MHz(), - dp.tim0, - )) - .unwrap(); - let mut delay_tim1 = CountdownTimer::new(&mut dp.sysconfig, 50.MHz(), dp.tim1); - let porta = PinsA::new(&mut dp.sysconfig, dp.porta); - let mut led1 = porta.pa10.into_readable_push_pull_output(); - let mut led2 = porta.pa7.into_readable_push_pull_output(); - let mut led3 = porta.pa6.into_readable_push_pull_output(); + let dp = pac::Peripherals::take().unwrap(); + let mut delay = CountdownTimer::new(50.MHz(), dp.tim1); + let porta = PinsA::new(dp.porta); + let mut led1 = Output::new(porta.pa10, PinState::Low); + let mut led2 = Output::new(porta.pa7, PinState::Low); + let mut led3 = Output::new(porta.pa6, PinState::Low); for _ in 0..10 { led1.set_low(); led2.set_low(); led3.set_low(); - delay_ms.delay_ms(200); + delay.delay_ms(200); led1.set_high(); led2.set_high(); led3.set_high(); - delay_tim1.delay_ms(200); + delay.delay_ms(200); } loop { led1.toggle(); - delay_ms.delay_ms(200); + delay.delay_ms(200); led2.toggle(); - delay_tim1.delay_ms(200); + delay.delay_ms(200); led3.toggle(); - delay_ms.delay_ms(200); + delay.delay_ms(200); } } - -#[interrupt] -#[allow(non_snake_case)] -fn OC0() { - default_ms_irq_handler() -} diff --git a/examples/simple/examples/cascade.rs b/examples/simple/examples/cascade.rs index bac4745..1bc952d 100644 --- a/examples/simple/examples/cascade.rs +++ b/examples/simple/examples/cascade.rs @@ -15,38 +15,27 @@ use rtt_target::{rprintln, rtt_init_print}; use va108xx_hal::{ pac::{self, interrupt}, prelude::*, - timer::{ - default_ms_irq_handler, set_up_ms_delay_provider, CascadeCtrl, CascadeSource, - CountdownTimer, Event, InterruptConfig, - }, + timer::{CascadeCtrl, CascadeSource, CountdownTimer, InterruptConfig}, }; -static CSD_TGT_1: Mutex>>> = - Mutex::new(RefCell::new(None)); -static CSD_TGT_2: Mutex>>> = - Mutex::new(RefCell::new(None)); +static CSD_TGT_1: Mutex>> = Mutex::new(RefCell::new(None)); +static CSD_TGT_2: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { rtt_init_print!(); rprintln!("-- VA108xx Cascade example application--"); - let mut dp = pac::Peripherals::take().unwrap(); - let mut delay = set_up_ms_delay_provider(&mut dp.sysconfig, 50.MHz(), dp.tim0); + let dp = pac::Peripherals::take().unwrap(); + let mut delay = CountdownTimer::new(50.MHz(), dp.tim0); // Will be started periodically to trigger a cascade - let mut cascade_triggerer = - CountdownTimer::new(&mut dp.sysconfig, 50.MHz(), dp.tim3).auto_disable(true); - cascade_triggerer.listen( - Event::TimeOut, - InterruptConfig::new(pac::Interrupt::OC1, true, false), - Some(&mut dp.irqsel), - Some(&mut dp.sysconfig), - ); + let mut cascade_triggerer = CountdownTimer::new(50.MHz(), dp.tim3).auto_disable(true); + cascade_triggerer.enable_interupt(InterruptConfig::new(pac::Interrupt::OC1, true, false)); + cascade_triggerer.enable(); // First target for cascade - let mut cascade_target_1 = - CountdownTimer::new(&mut dp.sysconfig, 50.MHz(), dp.tim4).auto_deactivate(true); + let mut cascade_target_1 = CountdownTimer::new(50.MHz(), dp.tim4).auto_deactivate(true); cascade_target_1 .cascade_0_source(CascadeSource::Tim(3)) .expect("Configuring cascade source for TIM4 failed"); @@ -60,19 +49,13 @@ fn main() -> ! { // Normally it should already be sufficient to activate IRQ in the CTRL // register but a full interrupt is use here to display print output when // the timer expires - cascade_target_1.listen( - Event::TimeOut, - InterruptConfig::new(pac::Interrupt::OC2, true, false), - Some(&mut dp.irqsel), - Some(&mut dp.sysconfig), - ); + cascade_target_1.enable_interupt(InterruptConfig::new(pac::Interrupt::OC2, true, false)); // The counter will only activate when the cascade signal is coming in so // it is okay to call start here to set the reset value cascade_target_1.start(1.Hz()); // Activated by first cascade target - let mut cascade_target_2 = - CountdownTimer::new(&mut dp.sysconfig, 50.MHz(), dp.tim5).auto_deactivate(true); + let mut cascade_target_2 = CountdownTimer::new(50.MHz(), dp.tim5).auto_deactivate(true); // Set TIM4 as cascade source cascade_target_2 .cascade_1_source(CascadeSource::Tim(4)) @@ -86,12 +69,7 @@ fn main() -> ! { // Normally it should already be sufficient to activate IRQ in the CTRL // register but a full interrupt is use here to display print output when // the timer expires - cascade_target_2.listen( - Event::TimeOut, - InterruptConfig::new(pac::Interrupt::OC3, true, false), - Some(&mut dp.irqsel), - Some(&mut dp.sysconfig), - ); + cascade_target_2.enable_interupt(InterruptConfig::new(pac::Interrupt::OC3, true, false)); // The counter will only activate when the cascade signal is coming in so // it is okay to call start here to set the reset value cascade_target_2.start(1.Hz()); @@ -115,11 +93,6 @@ fn main() -> ! { } } -#[interrupt] -fn OC0() { - default_ms_irq_handler() -} - #[interrupt] fn OC1() { static mut IDX: u32 = 0; diff --git a/examples/simple/examples/pwm.rs b/examples/simple/examples/pwm.rs index 57acac5..9b5beb5 100644 --- a/examples/simple/examples/pwm.rs +++ b/examples/simple/examples/pwm.rs @@ -7,33 +7,27 @@ use embedded_hal::{delay::DelayNs, pwm::SetDutyCycle}; use panic_rtt_target as _; use rtt_target::{rprintln, rtt_init_print}; use va108xx_hal::{ - gpio::PinsA, pac, + pins::PinsA, prelude::*, - pwm::{self, get_duty_from_percent, PwmA, PwmB, ReducedPwmPin}, - timer::set_up_ms_delay_provider, + pwm::{self, get_duty_from_percent, PwmA, PwmB, PwmPin}, + timer::CountdownTimer, }; #[entry] fn main() -> ! { rtt_init_print!(); rprintln!("-- VA108xx PWM example application--"); - let mut dp = pac::Peripherals::take().unwrap(); - let pinsa = PinsA::new(&mut dp.sysconfig, dp.porta); - let mut pwm = pwm::PwmPin::new( - &mut dp.sysconfig, - 50.MHz(), - (pinsa.pa3.into_funsel_1(), dp.tim3), - 10.Hz(), - ); - let mut delay = set_up_ms_delay_provider(&mut dp.sysconfig, 50.MHz(), dp.tim0); + let dp = pac::Peripherals::take().unwrap(); + let pinsa = PinsA::new(dp.porta); + let mut pwm = pwm::PwmPin::new(50.MHz(), (pinsa.pa3, dp.tim3), 10.Hz()).unwrap(); + let mut delay = CountdownTimer::new(50.MHz(), dp.tim0); let mut current_duty_cycle = 0.0; pwm.set_duty_cycle(get_duty_from_percent(current_duty_cycle)) .unwrap(); pwm.enable(); // Delete type information, increased code readibility for the rest of the code - let mut reduced_pin = ReducedPwmPin::from(pwm); loop { let mut counter = 0; // Increase duty cycle continuously @@ -45,8 +39,7 @@ fn main() -> ! { rprintln!("current duty cycle: {}", current_duty_cycle); } - reduced_pin - .set_duty_cycle(get_duty_from_percent(current_duty_cycle)) + pwm.set_duty_cycle(get_duty_from_percent(current_duty_cycle)) .unwrap(); } @@ -55,7 +48,7 @@ fn main() -> ! { current_duty_cycle = 0.0; let mut upper_limit = 1.0; let mut lower_limit = 0.0; - let mut pwmb: ReducedPwmPin = ReducedPwmPin::from(reduced_pin); + let mut pwmb: PwmPin = PwmPin::from(pwm); pwmb.set_pwmb_lower_limit(get_duty_from_percent(lower_limit)); pwmb.set_pwmb_upper_limit(get_duty_from_percent(upper_limit)); while lower_limit < 0.5 { @@ -67,6 +60,6 @@ fn main() -> ! { rprintln!("Lower limit: {}", pwmb.pwmb_lower_limit()); rprintln!("Upper limit: {}", pwmb.pwmb_upper_limit()); } - reduced_pin = ReducedPwmPin::::from(pwmb); + pwm = PwmPin::::from(pwmb); } } diff --git a/examples/simple/examples/spi.rs b/examples/simple/examples/spi.rs index 7869b5a..c67db93 100644 --- a/examples/simple/examples/spi.rs +++ b/examples/simple/examples/spi.rs @@ -12,11 +12,11 @@ use embedded_hal::{ use panic_rtt_target as _; use rtt_target::{rprintln, rtt_init_print}; use va108xx_hal::{ - gpio::{PinsA, PinsB}, pac::{self, interrupt}, + pins::{PinsA, PinsB}, prelude::*, - spi::{self, Spi, SpiBase, SpiClkConfig, TransferConfigWithHwcs}, - timer::{default_ms_irq_handler, set_up_ms_tick}, + spi::{self, configure_pin_as_hw_cs_pin, Spi, SpiClkConfig, TransferConfig}, + timer::CountdownTimer, InterruptConfig, }; @@ -46,20 +46,15 @@ fn main() -> ! { rtt_init_print!(); rprintln!("-- VA108xx SPI example application--"); let mut dp = pac::Peripherals::take().unwrap(); - let mut delay = set_up_ms_tick( - InterruptConfig::new(interrupt::OC0, true, true), - &mut dp.sysconfig, - Some(&mut dp.irqsel), - 50.MHz(), - dp.tim0, - ); + let mut delay = CountdownTimer::new(50.MHz(), dp.tim0); let spi_clk_cfg = SpiClkConfig::from_clk(50.MHz(), SPI_SPEED_KHZ.kHz()) .expect("creating SPI clock config failed"); - let spia_ref: RefCell>> = RefCell::new(None); - let spib_ref: RefCell>> = RefCell::new(None); - let pinsa = PinsA::new(&mut dp.sysconfig, dp.porta); - let pinsb = PinsB::new(&mut dp.sysconfig, dp.portb); + //let spia_ref: RefCell>> = RefCell::new(None); + //let spib_ref: RefCell>> = RefCell::new(None); + let spi = None; + let pinsa = PinsA::new(dp.porta); + let pinsb = PinsB::new(dp.portb); let mut spi_cfg = spi::SpiConfig::default(); if EXAMPLE_SEL == ExampleSelect::Loopback { @@ -67,158 +62,82 @@ fn main() -> ! { } // Set up the SPI peripheral - match SPI_BUS_SEL { + let spi = match SPI_BUS_SEL { SpiBusSelect::SpiAPortA => { - let (sck, mosi, miso) = ( - pinsa.pa31.into_funsel_1(), - pinsa.pa30.into_funsel_1(), - pinsa.pa29.into_funsel_1(), - ); - let mut spia = Spi::new( - &mut dp.sysconfig, - 50.MHz(), - dp.spia, - (sck, miso, mosi), - spi_cfg, - ); + let (sck, mosi, miso) = (pinsa.pa31, pinsa.pa30, pinsa.pa29); + let mut spia = Spi::new(50.MHz(), dp.spia, (sck, miso, mosi), spi_cfg).unwrap(); spia.set_fill_word(FILL_WORD); - spia_ref.borrow_mut().replace(spia.downgrade()); + spia } SpiBusSelect::SpiAPortB => { - let (sck, mosi, miso) = ( - pinsb.pb9.into_funsel_2(), - pinsb.pb8.into_funsel_2(), - pinsb.pb7.into_funsel_2(), - ); - let mut spia = Spi::new( - &mut dp.sysconfig, - 50.MHz(), - dp.spia, - (sck, miso, mosi), - spi_cfg, - ); + let (sck, mosi, miso) = (pinsb.pb9, pinsb.pb8, pinsb.pb7); + let mut spia = Spi::new(50.MHz(), dp.spia, (sck, miso, mosi), spi_cfg).unwrap(); spia.set_fill_word(FILL_WORD); - spia_ref.borrow_mut().replace(spia.downgrade()); + spia } SpiBusSelect::SpiBPortB => { - let (sck, mosi, miso) = ( - pinsb.pb5.into_funsel_1(), - pinsb.pb4.into_funsel_1(), - pinsb.pb3.into_funsel_1(), - ); - let mut spib = Spi::new( - &mut dp.sysconfig, - 50.MHz(), - dp.spib, - (sck, miso, mosi), - spi_cfg, - ); + let (sck, mosi, miso) = (pinsb.pb5, pinsb.pb4, pinsb.pb3); + let mut spib = Spi::new(50.MHz(), dp.spib, (sck, miso, mosi), spi_cfg).unwrap(); spib.set_fill_word(FILL_WORD); - spib_ref.borrow_mut().replace(spib.downgrade()); + spib } - } + }; // Configure transfer specific properties here match SPI_BUS_SEL { SpiBusSelect::SpiAPortA | SpiBusSelect::SpiAPortB => { - if let Some(ref mut spi) = *spia_ref.borrow_mut() { - let transfer_cfg = TransferConfigWithHwcs::new_no_hw_cs( - Some(spi_clk_cfg), - Some(SPI_MODE), - BLOCKMODE, - true, - false, - ); - spi.cfg_transfer(&transfer_cfg); - } + let transfer_cfg = TransferConfig { + clk_cfg: Some(spi_clk_cfg), + mode: Some(SPI_MODE), + sod: true, + blockmode: BLOCKMODE, + bmstall: true, + hw_cs: None, + }; + spi.cfg_transfer(&transfer_cfg); } SpiBusSelect::SpiBPortB => { - if let Some(ref mut spi) = *spib_ref.borrow_mut() { - let hw_cs_pin = pinsb.pb2.into_funsel_1(); - let transfer_cfg = TransferConfigWithHwcs::new( - Some(spi_clk_cfg), - Some(SPI_MODE), - Some(hw_cs_pin), - BLOCKMODE, - true, - false, - ); - spi.cfg_transfer(&transfer_cfg); - } + let hw_cs_pin = configure_pin_as_hw_cs_pin(pinsb.pb2); + let transfer_cfg = TransferConfig { + clk_cfg: Some(spi_clk_cfg), + mode: Some(SPI_MODE), + sod: false, + blockmode: BLOCKMODE, + bmstall: true, + hw_cs: Some(hw_cs_pin), + }; + spi.cfg_transfer(&transfer_cfg); } } // Application logic loop { let mut reply_buf: [u8; 8] = [0; 8]; - match SPI_BUS_SEL { - SpiBusSelect::SpiAPortA | SpiBusSelect::SpiAPortB => { - if let Some(ref mut spi) = *spia_ref.borrow_mut() { - // Can't really verify correct reply here. - spi.write(&[0x42]).expect("write failed"); - // Because of the loopback mode, we should get back the fill word here. - spi.read(&mut reply_buf[0..1]).unwrap(); - assert_eq!(reply_buf[0], FILL_WORD); - delay.delay_ms(500_u32); + // Can't really verify correct reply here. + spi.write(&[0x42]).expect("write failed"); + // Because of the loopback mode, we should get back the fill word here. + spi.read(&mut reply_buf[0..1]).unwrap(); + assert_eq!(reply_buf[0], FILL_WORD); + delay.delay_ms(500_u32); - let tx_buf: [u8; 3] = [0x01, 0x02, 0x03]; - spi.transfer(&mut reply_buf[0..3], &tx_buf).unwrap(); - assert_eq!(tx_buf, reply_buf[0..3]); - rprintln!( - "Received reply: {}, {}, {}", - reply_buf[0], - reply_buf[1], - reply_buf[2] - ); - delay.delay_ms(500_u32); + let tx_buf: [u8; 3] = [0x01, 0x02, 0x03]; + spi.transfer(&mut reply_buf[0..3], &tx_buf).unwrap(); + assert_eq!(tx_buf, reply_buf[0..3]); + rprintln!( + "Received reply: {}, {}, {}", + reply_buf[0], + reply_buf[1], + reply_buf[2] + ); + delay.delay_ms(500_u32); - let mut tx_rx_buf: [u8; 3] = [0x03, 0x02, 0x01]; - spi.transfer_in_place(&mut tx_rx_buf).unwrap(); - rprintln!( - "Received reply: {}, {}, {}", - tx_rx_buf[0], - tx_rx_buf[1], - tx_rx_buf[2] - ); - assert_eq!(&tx_rx_buf[0..3], &[0x03, 0x02, 0x01]); - } - } - SpiBusSelect::SpiBPortB => { - if let Some(ref mut spi) = *spib_ref.borrow_mut() { - // Can't really verify correct reply here. - spi.write(&[0x42]).expect("write failed"); - // Because of the loopback mode, we should get back the fill word here. - spi.read(&mut reply_buf[0..1]).unwrap(); - assert_eq!(reply_buf[0], FILL_WORD); - delay.delay_ms(500_u32); - - let tx_buf: [u8; 3] = [0x01, 0x02, 0x03]; - spi.transfer(&mut reply_buf[0..3], &tx_buf).unwrap(); - assert_eq!(tx_buf, reply_buf[0..3]); - rprintln!( - "Received reply: {}, {}, {}", - reply_buf[0], - reply_buf[1], - reply_buf[2] - ); - delay.delay_ms(500_u32); - - let mut tx_rx_buf: [u8; 3] = [0x03, 0x02, 0x01]; - spi.transfer_in_place(&mut tx_rx_buf).unwrap(); - rprintln!( - "Received reply: {}, {}, {}", - tx_rx_buf[0], - tx_rx_buf[1], - tx_rx_buf[2] - ); - assert_eq!(&tx_rx_buf[0..3], &[0x03, 0x02, 0x01]); - } - } - } + let mut tx_rx_buf: [u8; 3] = [0x03, 0x02, 0x01]; + spi.transfer_in_place(&mut tx_rx_buf).unwrap(); + rprintln!( + "Received reply: {}, {}, {}", + tx_rx_buf[0], + tx_rx_buf[1], + tx_rx_buf[2] + ); + assert_eq!(&tx_rx_buf[0..3], &[0x03, 0x02, 0x01]); } } - -#[interrupt] -#[allow(non_snake_case)] -fn OC0() { - default_ms_irq_handler() -} diff --git a/examples/simple/examples/timer-ticks.rs b/examples/simple/examples/timer-ticks.rs index 3b4b275..163c024 100644 --- a/examples/simple/examples/timer-ticks.rs +++ b/examples/simple/examples/timer-ticks.rs @@ -12,9 +12,7 @@ use va108xx_hal::{ pac::{self, interrupt}, prelude::*, time::Hertz, - timer::{ - default_ms_irq_handler, set_up_ms_tick, CountdownTimer, Event, InterruptConfig, MS_COUNTER, - }, + timer::{default_ms_irq_handler, CountdownTimer, Event, InterruptConfig, MS_COUNTER}, }; #[allow(dead_code)] @@ -66,21 +64,11 @@ fn main() -> ! { } } LibType::Hal => { - set_up_ms_tick( - InterruptConfig::new(interrupt::OC0, true, true), - &mut dp.sysconfig, - Some(&mut dp.irqsel), - 50.MHz(), - dp.tim0, - ); - let mut second_timer = - CountdownTimer::new(&mut dp.sysconfig, get_sys_clock().unwrap(), dp.tim1); - second_timer.listen( - Event::TimeOut, - InterruptConfig::new(interrupt::OC1, true, true), - Some(&mut dp.irqsel), - Some(&mut dp.sysconfig), - ); + let mut ms_timer = CountdownTimer::new(get_sys_clock().unwrap(), dp.tim0); + ms_timer.enable_interupt(InterruptConfig::new(interrupt::OC0, true, true)); + ms_timer.start(1.kHz()); + let mut second_timer = CountdownTimer::new(get_sys_clock().unwrap(), dp.tim1); + second_timer.enable_interupt(InterruptConfig::new(interrupt::OC1, true, true)); second_timer.start(1.Hz()); } } diff --git a/examples/simple/examples/uart.rs b/examples/simple/examples/uart.rs index 5869a03..d3bc8ba 100644 --- a/examples/simple/examples/uart.rs +++ b/examples/simple/examples/uart.rs @@ -15,25 +15,20 @@ use embedded_hal_nb::{nb, serial::Read}; use embedded_io::Write as _; use panic_rtt_target as _; use rtt_target::{rprintln, rtt_init_print}; -use va108xx_hal::{gpio::PinsA, pac, prelude::*, uart}; +use va108xx_hal::{pac, pins::PinsA, prelude::*, uart}; #[entry] fn main() -> ! { rtt_init_print!(); rprintln!("-- VA108xx UART example application--"); - let mut dp = pac::Peripherals::take().unwrap(); + let dp = pac::Peripherals::take().unwrap(); - let gpioa = PinsA::new(&mut dp.sysconfig, dp.porta); - let tx = gpioa.pa9.into_funsel_2(); - let rx = gpioa.pa8.into_funsel_2(); - let uart = uart::Uart::new_without_interrupt( - &mut dp.sysconfig, - 50.MHz(), - dp.uarta, - (tx, rx), - 115200.Hz(), - ); + let gpioa = PinsA::new(dp.porta); + let tx = gpioa.pa9; + let rx = gpioa.pa8; + let uart = uart::Uart::new_without_interrupt(50.MHz(), dp.uarta, (tx, rx), 115200.Hz().into()) + .unwrap(); let (mut tx, mut rx) = uart.split(); writeln!(tx, "Hello World\r").unwrap(); diff --git a/flashloader/Cargo.toml b/flashloader/Cargo.toml index a979b11..2215825 100644 --- a/flashloader/Cargo.toml +++ b/flashloader/Cargo.toml @@ -29,6 +29,7 @@ rtic-sync = {version = "1", features = ["defmt-03"]} [dependencies.va108xx-hal] version = "0.11" +path = "../va108xx-hal" features = ["defmt"] [dependencies.vorago-reb1] diff --git a/flashloader/src/main.rs b/flashloader/src/main.rs index 4928bfa..beeb505 100644 --- a/flashloader/src/main.rs +++ b/flashloader/src/main.rs @@ -68,7 +68,7 @@ mod app { use spacepackets::ecss::{ tc::PusTcReader, tm::PusTmCreator, EcssEnumU8, PusPacket, WritablePusPacket, }; - use va108xx_hal::gpio::PinsA; + use va108xx_hal::pins::PinsA; use va108xx_hal::uart::IrqContextTimeoutOrMaxSize; use va108xx_hal::{pac, uart, InterruptConfig}; use vorago_reb1::m95m01::M95M01; @@ -83,8 +83,8 @@ mod app { #[local] struct Local { - uart_rx: uart::RxWithInterrupt, - uart_tx: uart::Tx, + uart_rx: uart::RxWithInterrupt, + uart_tx: uart::Tx, rx_context: IrqContextTimeoutOrMaxSize, verif_reporter: VerificationReportCreator, nvm: M95M01, @@ -108,18 +108,18 @@ mod app { let mut dp = cx.device; let nvm = M95M01::new(&mut dp.sysconfig, SYSCLK_FREQ, dp.spic); - let gpioa = PinsA::new(&mut dp.sysconfig, dp.porta); - let tx = gpioa.pa9.into_funsel_2(); - let rx = gpioa.pa8.into_funsel_2(); + let gpioa = PinsA::new(dp.porta); + let tx = gpioa.pa9; + let rx = gpioa.pa8; let irq_uart = uart::Uart::new_with_interrupt( - &mut dp.sysconfig, SYSCLK_FREQ, dp.uarta, (tx, rx), - UART_BAUDRATE.Hz(), + UART_BAUDRATE.Hz().into(), InterruptConfig::new(pac::Interrupt::OC0, true, true), - ); + ) + .unwrap(); let (tx, rx) = irq_uart.split(); // Unwrap is okay, we explicitely set the interrupt ID. let mut rx = rx.into_rx_with_irq(); diff --git a/va108xx-embassy/Cargo.toml b/va108xx-embassy/Cargo.toml index e7520ba..e1ebb69 100644 --- a/va108xx-embassy/Cargo.toml +++ b/va108xx-embassy/Cargo.toml @@ -20,7 +20,7 @@ embassy-time-queue-utils = "0.1" once_cell = { version = "1", default-features = false, features = ["critical-section"] } -va108xx-hal = { version = ">=0.10, <=0.11" } +va108xx-hal = { version = ">=0.10, <=0.11", path = "../va108xx-hal" } [target.'cfg(all(target_arch = "arm", target_os = "none"))'.dependencies] portable-atomic = { version = "1", features = ["unsafe-assume-single-core"] } diff --git a/va108xx-embassy/src/lib.rs b/va108xx-embassy/src/lib.rs index dce3ef7..b4d6b81 100644 --- a/va108xx-embassy/src/lib.rs +++ b/va108xx-embassy/src/lib.rs @@ -45,7 +45,7 @@ use va108xx_hal::{ clock::enable_peripheral_clock, enable_nvic_interrupt, pac, prelude::*, - timer::{enable_tim_clk, get_tim_raw, TimRegInterface, ValidTim}, + timer::{enable_tim_clk, get_tim_raw, TimMarker, TimRegInterface}, PeripheralSelect, }; @@ -109,48 +109,28 @@ pub fn time_driver() -> &'static TimerDriver { /// This should be used if the interrupt handler is provided by the library, which is the /// default case. #[cfg(feature = "irqs-in-lib")] -pub fn init( - syscfg: &mut pac::Sysconfig, - irqsel: &pac::Irqsel, - sysclk: impl Into, +pub fn init( + sysclk: Hertz, timekeeper_tim: TimekeeperTim, alarm_tim: AlarmTim, ) { - TIME_DRIVER.init( - syscfg, - irqsel, - sysclk, - timekeeper_tim, - alarm_tim, - TIMEKEEPER_IRQ, - ALARM_IRQ, - ) + TIME_DRIVER.init(sysclk, timekeeper_tim, alarm_tim, TIMEKEEPER_IRQ, ALARM_IRQ) } /// Initialization method for embassy when using custom IRQ handlers. /// /// Requires an explicit [pac::Interrupt] argument for the timekeeper and alarm IRQs. pub fn init_with_custom_irqs< - TimekeeperTim: TimRegInterface + ValidTim, - AlarmTim: TimRegInterface + ValidTim, + TimekeeperTim: TimRegInterface + TimMarker, + AlarmTim: TimRegInterface + TimMarker, >( - syscfg: &mut pac::Sysconfig, - irqsel: &pac::Irqsel, - sysclk: impl Into, + sysclk: Hertz, timekeeper_tim: TimekeeperTim, alarm_tim: AlarmTim, timekeeper_irq: pac::Interrupt, alarm_irq: pac::Interrupt, ) { - TIME_DRIVER.init( - syscfg, - irqsel, - sysclk, - timekeeper_tim, - alarm_tim, - timekeeper_irq, - alarm_irq, - ) + TIME_DRIVER.init(sysclk, timekeeper_tim, alarm_tim, timekeeper_irq, alarm_irq) } struct AlarmState { @@ -180,11 +160,9 @@ pub struct TimerDriver { impl TimerDriver { #[allow(clippy::too_many_arguments)] - fn init( + fn init( &self, - syscfg: &mut pac::Sysconfig, - irqsel: &pac::Irqsel, - sysclk: impl Into, + sysclk: Hertz, timekeeper_tim: TimekeeperTim, alarm_tim: AlarmTim, timekeeper_irq: pac::Interrupt, @@ -193,13 +171,12 @@ impl TimerDriver { if ALARM_TIM.get().is_some() || TIMEKEEPER_TIM.get().is_some() { return; } - ALARM_TIM.set(AlarmTim::TIM_ID).ok(); - TIMEKEEPER_TIM.set(TimekeeperTim::TIM_ID).ok(); - enable_peripheral_clock(syscfg, PeripheralSelect::Irqsel); - enable_tim_clk(syscfg, timekeeper_tim.tim_id()); + ALARM_TIM.set(AlarmTim::ID.raw_id()).ok(); + TIMEKEEPER_TIM.set(TimekeeperTim::ID.raw_id()).ok(); + enable_peripheral_clock(PeripheralSelect::Irqsel); + enable_tim_clk(timekeeper_tim.raw_id()); let timekeeper_reg_block = timekeeper_tim.reg_block(); let alarm_tim_reg_block = alarm_tim.reg_block(); - let sysclk = sysclk.into(); // Initiate scale value here. This is required to convert timer ticks back to a timestamp. SCALE.set((sysclk.raw() / TICK_HZ as u32) as u64).unwrap(); timekeeper_reg_block @@ -209,9 +186,10 @@ impl TimerDriver { timekeeper_reg_block .cnt_value() .write(|w| unsafe { w.bits(u32::MAX) }); + let irqsel = unsafe { va108xx_hal::pac::Irqsel::steal() }; // Switch on. Timekeeping should always be done. irqsel - .tim0(timekeeper_tim.tim_id() as usize) + .tim0(timekeeper_tim.raw_id() as usize) .write(|w| unsafe { w.bits(timekeeper_irq as u32) }); unsafe { enable_nvic_interrupt(timekeeper_irq); @@ -223,7 +201,7 @@ impl TimerDriver { .enable() .write(|w| unsafe { w.bits(1) }); - enable_tim_clk(syscfg, alarm_tim.tim_id()); + enable_tim_clk(alarm_tim.raw_id()); // Explicitely disable alarm timer until needed. alarm_tim_reg_block.ctrl().modify(|_, w| { @@ -235,7 +213,7 @@ impl TimerDriver { enable_nvic_interrupt(alarm_irq); } irqsel - .tim0(alarm_tim.tim_id() as usize) + .tim0(alarm_tim.raw_id() as usize) .write(|w| unsafe { w.bits(alarm_irq as u32) }); } diff --git a/va108xx-hal/src/clock.rs b/va108xx-hal/src/clock.rs index 702cc49..6e9970a 100644 --- a/va108xx-hal/src/clock.rs +++ b/va108xx-hal/src/clock.rs @@ -2,24 +2,13 @@ //! //! This also includes functionality to enable the peripheral clocks use crate::time::Hertz; -use crate::PeripheralSelect; use cortex_m::interrupt::{self, Mutex}; use once_cell::unsync::OnceCell; -static SYS_CLOCK: Mutex> = Mutex::new(OnceCell::new()); +pub use vorago_shared_periphs::gpio::FilterClkSel; +pub use vorago_shared_periphs::sysconfig::{disable_peripheral_clock, enable_peripheral_clock}; -#[derive(Debug, PartialEq, Eq)] -#[cfg_attr(feature = "defmt", derive(defmt::Format))] -pub enum FilterClkSel { - SysClk = 0, - Clk1 = 1, - Clk2 = 2, - Clk3 = 3, - Clk4 = 4, - Clk5 = 5, - Clk6 = 6, - Clk7 = 7, -} +static SYS_CLOCK: Mutex> = Mutex::new(OnceCell::new()); /// The Vorago in powered by an external clock which might have different frequencies. /// The clock can be set here so it can be used by other software components as well. @@ -61,5 +50,3 @@ pub fn set_clk_div_register(syscfg: &mut va108xx::Sysconfig, clk_sel: FilterClkS } } } - -pub use vorago_shared_periphs::sysconfig::{disable_peripheral_clock, enable_peripheral_clock}; diff --git a/va108xx-hal/src/i2c.rs b/va108xx-hal/src/i2c.rs index 652f59f..83668be 100644 --- a/va108xx-hal/src/i2c.rs +++ b/va108xx-hal/src/i2c.rs @@ -307,7 +307,7 @@ impl I2cBase { impl I2cBase { pub fn new( - sysclk: Hertz, + sys_clk: Hertz, i2c: I2c, speed_mode: I2cSpeed, ms_cfg: Option<&MasterConfig>, @@ -315,10 +315,7 @@ impl I2cBase { ) -> Result { enable_peripheral_clock(I2c::PERIPH_SEL); - let mut i2c_base = I2cBase { - i2c, - sys_clk: sysclk.into(), - }; + let mut i2c_base = I2cBase { i2c, sys_clk }; if let Some(ms_cfg) = ms_cfg { i2c_base.cfg_master(ms_cfg); } diff --git a/va108xx-hal/src/pins.rs b/va108xx-hal/src/pins.rs index ce07e71..c025a04 100644 --- a/va108xx-hal/src/pins.rs +++ b/va108xx-hal/src/pins.rs @@ -1,6 +1,13 @@ -pub use vorago_shared_periphs::gpio::{Pin, PinId, PinMarker, Port}; +use vorago_shared_periphs::sysconfig::reset_peripheral_for_cycles; -use crate::{sysconfig::reset_peripheral_for_cycles, PeripheralSelect}; +pub use crate::gpio::{Pin, PinId, PinIdProvider, Port}; + +use crate::sealed::Sealed; +use crate::PeripheralSelect; + +pub trait PinMarker: Sealed { + const ID: PinId; +} macro_rules! pin_id { ($Id:ident, $Port:path, $num:literal) => { @@ -11,14 +18,18 @@ macro_rules! pin_id { pub enum $Id {} impl $crate::sealed::Sealed for $Id {} - impl PinMarker for $Id { - const ID: PinId = PinId::new($Port, $num); + impl PinIdProvider for $Id { + const ID: PinId = PinId::new_unchecked($Port, $num); + } + + impl PinMarker for Pin<$Id> { + const ID: PinId = $Id::ID; } } }; } -impl crate::sealed::Sealed for Pin {} +impl Sealed for Pin {} pin_id!(Pa0, Port::A, 0); pin_id!(Pa1, Port::A, 1); diff --git a/va108xx-hal/src/pwm.rs b/va108xx-hal/src/pwm.rs index 0ea48af..70e6ba6 100644 --- a/va108xx-hal/src/pwm.rs +++ b/va108xx-hal/src/pwm.rs @@ -8,10 +8,11 @@ use core::convert::Infallible; use core::marker::PhantomData; +use vorago_shared_periphs::PeripheralSelect; + use crate::clock::enable_peripheral_clock; -use crate::pac; use crate::time::Hertz; -use crate::timer::{TimId, TimPeripheralMarker, TimPin, TimRegInterface}; +use crate::timer::{TimId, TimMarker, TimPin, TimRegInterface}; const DUTY_MAX: u16 = u16::MAX; @@ -56,9 +57,8 @@ pub struct PwmPin { impl PwmPin { /// Create a new strongly typed PWM pin - pub fn new( - sys_cfg: &mut pac::Sysconfig, - sys_clk: impl Into + Copy, + pub fn new( + sys_clk: Hertz, pin_and_tim: (Pin, Tim), initial_period: impl Into + Copy, ) -> Result { @@ -74,12 +74,13 @@ impl PwmPin { current_lower_limit: 0, current_period: initial_period.into(), current_rst_val: 0, - sys_clk: sys_clk.into(), + sys_clk, mode: PhantomData, }; - enable_peripheral_clock(crate::clock::PeripheralClocks::Gpio); - enable_peripheral_clock(crate::clock::PeripheralClocks::Ioconfig); - sys_cfg + enable_peripheral_clock(PeripheralSelect::Gpio); + enable_peripheral_clock(PeripheralSelect::Ioconfig); + let syscfg = unsafe { va108xx::Sysconfig::steal() }; + syscfg .tim_clk_enable() .modify(|r, w| unsafe { w.bits(r.bits() | pin_and_tim.1.mask_32()) }); pin.enable_pwm_a(); diff --git a/va108xx-hal/src/spi/mod.rs b/va108xx-hal/src/spi/mod.rs index bf65854..af2d8d4 100644 --- a/va108xx-hal/src/spi/mod.rs +++ b/va108xx-hal/src/spi/mod.rs @@ -9,13 +9,22 @@ //! - [Blocking SPI example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples/simple/examples/spi.rs) //! - [REB1 ADC example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/vorago-reb1/examples/max11519-adc.rs) //! - [REB1 EEPROM library](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/vorago-reb1/src/m95m01.rs) -use crate::{clock::enable_peripheral_clock, pac, time::Hertz, PeripheralSelect}; +use crate::{ + clock::enable_peripheral_clock, pac, pins::PinMarker, sealed::Sealed, time::Hertz, + PeripheralSelect, +}; use core::{convert::Infallible, fmt::Debug, marker::PhantomData, ops::Deref}; use embedded_hal::spi::{Mode, MODE_0}; use pins::{HwCsProvider, PinMiso, PinMosi, PinSck}; +use vorago_shared_periphs::gpio::IoPeriphPin; pub mod pins; +pub fn configure_pin_as_hw_cs_pin(_pin: P) -> HwChipSelectId { + IoPeriphPin::new(P::ID, P::FUN_SEL, None); + P::CS_ID +} + //================================================================================================== // Defintions //================================================================================================== @@ -41,7 +50,7 @@ pub enum HwChipSelectId { Id7 = 7, } -#[derive(Debug)] +#[derive(Debug, PartialEq, Eq)] #[cfg_attr(feature = "defmt", derive(defmt::Format))] pub enum SpiId { A, @@ -80,7 +89,7 @@ pub type SpiRegBlock = pac::spia::RegisterBlock; /// Common trait implemented by all PAC peripheral access structures. The register block /// format is the same for all SPI blocks. -pub trait SpiPeripheralMarker: Deref { +pub trait SpiMarker: Deref + Sealed { const ID: SpiId; const PERIPH_SEL: PeripheralSelect; @@ -92,7 +101,7 @@ pub trait SpiPeripheralMarker: Deref { } } -impl SpiPeripheralMarker for pac::Spia { +impl SpiMarker for pac::Spia { const ID: SpiId = SpiId::A; const PERIPH_SEL: PeripheralSelect = PeripheralSelect::Spi0; @@ -101,8 +110,9 @@ impl SpiPeripheralMarker for pac::Spia { Self::ptr() } } +impl Sealed for pac::Spia {} -impl SpiPeripheralMarker for pac::Spib { +impl SpiMarker for pac::Spib { const ID: SpiId = SpiId::B; const PERIPH_SEL: PeripheralSelect = PeripheralSelect::Spi1; @@ -111,8 +121,9 @@ impl SpiPeripheralMarker for pac::Spib { Self::ptr() } } +impl Sealed for pac::Spib {} -impl SpiPeripheralMarker for pac::Spic { +impl SpiMarker for pac::Spic { const ID: SpiId = SpiId::C; const PERIPH_SEL: PeripheralSelect = PeripheralSelect::Spi2; @@ -121,6 +132,7 @@ impl SpiPeripheralMarker for pac::Spic { Self::ptr() } } +impl Sealed for pac::Spic {} //================================================================================================== // Config @@ -134,17 +146,6 @@ pub trait TransferConfigProvider { fn hw_cs_id(&self) -> u8; } -/* -/// This struct contains all configuration parameter which are transfer specific -/// and might change for transfers to different SPI slaves -#[derive(Copy, Clone, Debug)] -#[cfg_attr(feature = "defmt", derive(defmt::Format))] -pub struct TransferConfigWithHwcs { - pub hw_cs: Option, - pub cfg: TransferConfig, -} -*/ - /// Type erased variant of the transfer configuration. This is required to avoid generics in /// the SPI constructor. #[derive(Copy, Clone, Debug)] @@ -163,80 +164,26 @@ pub struct TransferConfig { pub hw_cs: Option, } -/* -impl TransferConfigWithHwcs { - pub fn new_no_hw_cs( +impl TransferConfig { + pub fn new_with_hw_cs( clk_cfg: Option, mode: Option, blockmode: bool, bmstall: bool, sod: bool, + hw_cs_id: HwChipSelectId, ) -> Self { - TransferConfigWithHwcs { - hw_cs: None, - cfg: TransferConfig { - clk_cfg, - mode, - sod, - blockmode, - bmstall, - hw_cs: HwChipSelectId::Invalid, - }, + TransferConfig { + clk_cfg, + mode, + sod, + blockmode, + bmstall, + hw_cs: Some(hw_cs_id), } } } -impl TransferConfigWithHwcs { - pub fn new( - clk_cfg: Option, - mode: Option, - hw_cs: Option, - blockmode: bool, - bmstall: bool, - sod: bool, - ) -> Self { - TransferConfigWithHwcs { - hw_cs, - cfg: TransferConfig { - clk_cfg, - mode, - sod, - blockmode, - bmstall, - hw_cs: HwCs::CS_ID, - }, - } - } - - pub fn downgrade(self) -> TransferConfig { - self.cfg - } -} - -impl TransferConfigProvider for TransferConfigWithHwcs { - /// Slave Output Disable - fn sod(&mut self, sod: bool) { - self.cfg.sod = sod; - } - - fn blockmode(&mut self, blockmode: bool) { - self.cfg.blockmode = blockmode; - } - - fn mode(&mut self, mode: Mode) { - self.cfg.mode = Some(mode); - } - - fn clk_cfg(&mut self, clk_cfg: SpiClkConfig) { - self.cfg.clk_cfg = Some(clk_cfg); - } - - fn hw_cs_id(&self) -> u8 { - HwCs::CS_ID as u8 - } -} -*/ - /// Configuration options for the whole SPI bus. See Programmer Guide p.92 for more details #[derive(Debug, Copy, Clone)] #[cfg_attr(feature = "defmt", derive(defmt::Format))] @@ -373,25 +320,6 @@ pub trait SpiLowLevel { fn read_fifo_unchecked(&mut self) -> u32; } -pub struct Spi { - id: SpiId, - reg_block: *mut SpiRegBlock, - cfg: SpiConfig, - sys_clk: Hertz, - /// Fill word for read-only SPI transactions. - pub fill_word: Word, - blockmode: bool, - bmstall: bool, - word: PhantomData, -} - -/* -pub struct Spi<, Pins, Word = u8> { - inner: SpiBase, - pins: Pins, -} -*/ - #[inline(always)] pub fn mode_to_cpo_cph_bit(mode: embedded_hal::spi::Mode) -> (bool, bool) { match mode { @@ -510,28 +438,69 @@ pub fn clk_div_for_target_clock( Some(rounded_div as u16) } +#[derive(Debug, thiserror::Error)] +#[error("peripheral or peripheral pin ID is not consistent")] +pub struct SpiIdMissmatchError; + +/// SPI peripheral driver structure. +pub struct Spi { + id: SpiId, + reg_block: *mut SpiRegBlock, + cfg: SpiConfig, + sys_clk: Hertz, + /// Fill word for read-only SPI transactions. + fill_word: Word, + blockmode: bool, + bmstall: bool, + word: PhantomData, +} + impl Spi where >::Error: core::fmt::Debug, { - /// Create a new SPI struct - /// - /// You can delete the pin type information by calling the - /// [`downgrade`](Self::downgrade) function + /// Create a new SPI struct. /// /// ## Arguments - /// * `syscfg` - Can be passed optionally to enable the peripheral clock /// * `sys_clk` - System clock /// * `spi` - SPI bus to use /// * `pins` - Pins to be used for SPI transactions. These pins are consumed /// to ensure the pins can not be used for other purposes anymore /// * `spi_cfg` - Configuration specific to the SPI bus - pub fn new( - sys_clk: impl Into, + pub fn new_for_rom( + sys_clk: Hertz, + spi: SpiI, + spi_cfg: SpiConfig, + ) -> Result { + if SpiI::ID != SpiId::C { + return Err(SpiIdMissmatchError); + } + Ok(Self::new_generic(sys_clk, spi, spi_cfg)) + } + /// Create a new SPI struct. + /// + /// ## Arguments + /// * `sys_clk` - System clock + /// * `spi` - SPI bus to use + /// * `pins` - Pins to be used for SPI transactions. These pins are consumed + /// to ensure the pins can not be used for other purposes anymore + /// * `spi_cfg` - Configuration specific to the SPI bus + pub fn new( + sys_clk: Hertz, spi: SpiI, _pins: (Sck, Miso, Mosi), spi_cfg: SpiConfig, - ) -> Self { + ) -> Result { + if SpiI::ID != Sck::SPI_ID || SpiI::ID != Miso::SPI_ID || SpiI::ID != Mosi::SPI_ID { + return Err(SpiIdMissmatchError); + } + IoPeriphPin::new(Sck::ID, Sck::FUN_SEL, None); + IoPeriphPin::new(Miso::ID, Miso::FUN_SEL, None); + IoPeriphPin::new(Mosi::ID, Mosi::FUN_SEL, None); + Ok(Self::new_generic(sys_clk, spi, spi_cfg)) + } + + pub fn new_generic(sys_clk: Hertz, spi: SpiI, spi_cfg: SpiConfig) -> Self { enable_peripheral_clock(SpiI::PERIPH_SEL); let (cpo_bit, cph_bit) = mode_to_cpo_cph_bit(spi_cfg.init_mode); spi.ctrl0().write(|w| { @@ -568,7 +537,7 @@ where id: SpiI::ID, reg_block: spi.reg_block(), cfg: spi_cfg, - sys_clk: sys_clk.into(), + sys_clk, fill_word: Default::default(), bmstall: spi_cfg.bmstall, blockmode: spi_cfg.blockmode, @@ -596,6 +565,10 @@ where .write(|w| unsafe { w.bits(cfg.prescale_val as u32) }); } + pub fn set_fill_word(&mut self, fill_word: Word) { + self.fill_word = fill_word; + } + #[inline] pub fn cfg_clock_from_div(&mut self, div: u16) -> Result<(), SpiClkConfigError> { let val = spi_clk_config_from_div(div)?; @@ -633,6 +606,10 @@ where } /// Configure the hardware chip select given a hardware chip select ID. + /// + /// The pin also needs to be configured to be used as a HW CS pin. This can be done + /// by using the [configure_pin_as_hw_cs_pin] function which also returns the + /// corresponding [HwChipSelectId]. #[inline] pub fn cfg_hw_cs(&mut self, hw_cs: HwChipSelectId) { self.reg_block_mut().ctrl1().modify(|_, w| { @@ -644,13 +621,6 @@ where }); } - /// Configure the hardware chip select given a physical hardware CS pin. - #[inline] - pub fn cfg_hw_cs_with_pin(&mut self, _: &HwCs) { - // TODO: Error handling. - self.cfg_hw_cs(HwCs::CS_ID); - } - /// Disables the hardware chip select functionality. This can be used when performing /// external chip select handling, for example with GPIO pins. #[inline] diff --git a/va108xx-hal/src/spi/pins.rs b/va108xx-hal/src/spi/pins.rs index 590a1bb..7cb40ee 100644 --- a/va108xx-hal/src/spi/pins.rs +++ b/va108xx-hal/src/spi/pins.rs @@ -1,32 +1,33 @@ +use vorago_shared_periphs::gpio::{PinId, PinIdProvider}; use vorago_shared_periphs::FunSel; use crate::{ pins::{ Pa10, Pa11, Pa12, Pa13, Pa14, Pa15, Pa16, Pa17, Pa18, Pa19, Pa20, Pa21, Pa22, Pa23, Pa24, Pa25, Pa26, Pa27, Pa28, Pa29, Pa30, Pa31, Pb0, Pb1, Pb10, Pb11, Pb12, Pb13, Pb14, Pb15, - Pb16, Pb17, Pb18, Pb19, Pb2, Pb22, Pb23, Pb3, Pb4, Pb5, Pb6, Pb7, Pb8, Pb9, Pin, + Pb16, Pb17, Pb18, Pb19, Pb2, Pb22, Pb23, Pb3, Pb4, Pb5, Pb6, Pb7, Pb8, Pb9, Pin, PinMarker, }, sealed::Sealed, }; use super::{HwChipSelectId, SpiId}; -pub trait PinSck: Sealed { +pub trait PinSck: PinMarker { const SPI_ID: SpiId; const FUN_SEL: FunSel; } -pub trait PinMosi: Sealed { +pub trait PinMosi: PinMarker { const SPI_ID: SpiId; const FUN_SEL: FunSel; } -pub trait PinMiso: Sealed { +pub trait PinMiso: PinMarker { const SPI_ID: SpiId; const FUN_SEL: FunSel; } -pub trait HwCsProvider: Sealed { +pub trait HwCsProvider: PinMarker { const SPI_ID: SpiId; const FUN_SEL: FunSel; const CS_ID: HwChipSelectId; @@ -48,7 +49,7 @@ macro_rules! hw_cs_multi_pin { // name of the newtype wrapper struct $name:ident, // Pb0 - $pin_id:path, + $pin_id:ident, // SpiId::B $spi_id:path, // FunSel::Sel1 @@ -71,6 +72,10 @@ macro_rules! hw_cs_multi_pin { impl Sealed for $name {} + impl PinMarker for $name { + const ID: PinId = <$pin_id as PinIdProvider>::ID; + } + impl HwCsProvider for $name { const SPI_ID: SpiId = $spi_id; const FUN_SEL: FunSel = $fun_sel; @@ -185,7 +190,7 @@ impl PinMosi for Pin { const SPI_ID: SpiId = SpiId::B; const FUN_SEL: FunSel = FunSel::Sel2; } -impl PinMosi for Pin { +impl PinMiso for Pin { const SPI_ID: SpiId = SpiId::B; const FUN_SEL: FunSel = FunSel::Sel2; } @@ -202,7 +207,7 @@ impl PinMosi for Pin { const SPI_ID: SpiId = SpiId::B; const FUN_SEL: FunSel = FunSel::Sel1; } -impl PinMosi for Pin { +impl PinMiso for Pin { const SPI_ID: SpiId = SpiId::B; const FUN_SEL: FunSel = FunSel::Sel1; } @@ -215,7 +220,7 @@ impl PinMosi for Pin { const SPI_ID: SpiId = SpiId::B; const FUN_SEL: FunSel = FunSel::Sel1; } -impl PinMosi for Pin { +impl PinMiso for Pin { const SPI_ID: SpiId = SpiId::B; const FUN_SEL: FunSel = FunSel::Sel1; } @@ -330,6 +335,7 @@ hw_cs_multi_pin!( // SPIC +/* // Dummy pin defintion for the ROM SCK. pub struct RomSck; // Dummy pin defintion for the ROM MOSI. @@ -358,6 +364,7 @@ impl PinMiso for RomMiso { const FUN_SEL: FunSel = FunSel::Sel0; } impl Sealed for RomCs {} +*/ hw_cs_pins!( SpiId::C, @@ -408,9 +415,11 @@ hw_cs_multi_pin!( HwChipSelectId::Id4 ); +/* impl HwCsProvider for RomCs { const CS_ID: HwChipSelectId = HwChipSelectId::Id0; const SPI_ID: SpiId = SpiId::C; /// Function select does not make sense here, just select default value. const FUN_SEL: FunSel = FunSel::Sel0; } +*/ diff --git a/va108xx-hal/src/sysconfig.rs b/va108xx-hal/src/sysconfig.rs index 4122e27..b664761 100644 --- a/va108xx-hal/src/sysconfig.rs +++ b/va108xx-hal/src/sysconfig.rs @@ -1,5 +1,3 @@ -use crate::PeripheralSelect; - #[derive(PartialEq, Eq, Debug)] #[cfg_attr(feature = "defmt", derive(defmt::Format))] pub struct InvalidCounterResetVal(pub(crate) ()); @@ -40,26 +38,6 @@ pub fn disable_ram_scrubbing() { syscfg.ram_scrub().write(|w| unsafe { w.bits(0) }); } -#[inline] -pub fn assert_peripheral_reset(periph_sel: PeripheralSelect) { - let syscfg = unsafe { va108xx::Sysconfig::steal() }; - syscfg - .peripheral_reset() - .modify(|r, w| unsafe { w.bits(r.bits() & !(1 << periph_sel as u8)) }); -} - -#[inline] -pub fn deassert_peripheral_reset(periph_sel: PeripheralSelect) { - let syscfg = unsafe { va108xx::Sysconfig::steal() }; - syscfg - .peripheral_reset() - .modify(|r, w| unsafe { w.bits(r.bits() | (1 << periph_sel as u8)) }); -} - -pub fn reset_peripheral_for_cycles(periph_sel: PeripheralSelect, cycles: u32) { - assert_peripheral_reset(periph_sel); - cortex_m::asm::delay(cycles); - deassert_peripheral_reset(periph_sel); -} - -pub use vorago_shared_periphs::sysconfig::{disable_peripheral_clock, enable_peripheral_clock}; +pub use vorago_shared_periphs::sysconfig::{ + assert_peripheral_reset, disable_peripheral_clock, enable_peripheral_clock, +}; diff --git a/va108xx-hal/src/timer.rs b/va108xx-hal/src/timer.rs index d7ca759..8d0910c 100644 --- a/va108xx-hal/src/timer.rs +++ b/va108xx-hal/src/timer.rs @@ -16,17 +16,13 @@ use crate::{ sealed::Sealed, time::Hertz, }; -use core::cell::Cell; -use critical_section::Mutex; use fugit::RateExtU32; use vorago_shared_periphs::{ - gpio::{Pin, PinMarker}, + gpio::{Pin, PinIdProvider}, ioconfig::regs::FunSel, Port, }; -pub static MS_COUNTER: Mutex> = Mutex::new(Cell::new(0)); - /// Get the peripheral block of a TIM peripheral given the index. /// /// This function panics if the given index is greater than 23. @@ -170,17 +166,23 @@ pub trait TimPin: Sealed { const TIM_ID: TimId; } -pub trait TimPeripheralMarker: Sealed { +pub trait TimMarker: Sealed { // TIM ID ranging from 0 to 23 for 24 TIM peripherals const ID: TimId; } macro_rules! tim_marker { ($TIMX:path, $ID:expr) => { - impl TimPeripheralMarker for $TIMX { + impl TimMarker for $TIMX { const ID: TimId = TimId($ID); } + unsafe impl TimRegInterface for $TIMX { + fn raw_id(&self) -> u8 { + Self::ID.0 + } + } + impl Sealed for $TIMX {} }; } @@ -210,13 +212,13 @@ tim_marker!(pac::Tim21, 21); tim_marker!(pac::Tim22, 22); tim_marker!(pac::Tim23, 23); -pub trait ValidTimAndPin: Sealed {} +pub trait ValidTimAndPin: Sealed {} macro_rules! pin_and_tim { ($Px:ident, $FunSel:path, $ID:expr) => { impl TimPin for Pin<$Px> where - $Px: PinMarker, + $Px: PinIdProvider, { const PORT: Port = $Px::ID.port(); const OFFSET: usize = $Px::ID.offset(); @@ -368,7 +370,7 @@ unsafe impl TimRegInterface for CountdownTimer { impl CountdownTimer { /// Configures a TIM peripheral as a periodic count down timer - pub fn new(sys_clk: Hertz, _tim: Tim) -> Self { + pub fn new(sys_clk: Hertz, _tim: Tim) -> Self { enable_tim_clk(Tim::ID.raw_id()); let cd_timer = CountdownTimer { tim: Tim::ID, @@ -593,6 +595,10 @@ impl CountdownTimer { } } +//================================================================================================== +// Delay implementations +//================================================================================================== +// impl embedded_hal::delay::DelayNs for CountdownTimer { fn delay_ns(&mut self, ns: u32) { let ticks = (u64::from(ns)) * (u64::from(self.sys_clk.raw())) / 1_000_000_000; @@ -647,59 +653,6 @@ impl embedded_hal::delay::DelayNs for CountdownTimer { } } -pub fn set_up_ms_delay_provider(sys_clk: Hertz, tim: impl TimPeripheralMarker) -> CountdownTimer { - let mut provider = CountdownTimer::new(sys_clk, tim); - provider.start(1000.Hz()); - provider -} - -/// This function can be called in a specified interrupt handler to increment -/// the MS counter -pub fn default_ms_irq_handler() { - critical_section::with(|cs| { - let mut ms = MS_COUNTER.borrow(cs).get(); - ms += 1; - MS_COUNTER.borrow(cs).set(ms); - }); -} - -/// Get the current MS tick count -pub fn get_ms_ticks() -> u32 { - critical_section::with(|cs| MS_COUNTER.borrow(cs).get()) -} - -//================================================================================================== -// Delay implementations -//================================================================================================== - -/* -pub struct DelayMs(CountdownTimer); - -impl DelayMs { - pub fn new(timer: CountdownTimer) -> Option { - if timer.curr_freq() != Hertz::from_raw(1000) || !timer.listening() { - return None; - } - Some(Self(timer)) - } -} - -/// This assumes that the user has already set up a MS tick timer in TIM0 as a system tick -/// with [`set_up_ms_delay_provider`] -impl embedded_hal::delay::DelayNs for DelayMs { - fn delay_ns(&mut self, ns: u32) { - let ns_as_ms = ns / 1_000_000; - if self.0.curr_freq() != Hertz::from_raw(1000) || !self.0.listening() { - return; - } - let start_time = get_ms_ticks(); - while get_ms_ticks() - start_time < ns_as_ms { - cortex_m::asm::nop(); - } - } -} -*/ - #[inline(always)] pub fn enable_tim_clk(idx: u8) { let syscfg = unsafe { va108xx::Sysconfig::steal() }; diff --git a/va108xx-hal/src/uart/mod.rs b/va108xx-hal/src/uart/mod.rs index 0e6f7d2..e1ffb1d 100644 --- a/va108xx-hal/src/uart/mod.rs +++ b/va108xx-hal/src/uart/mod.rs @@ -14,7 +14,10 @@ //! - [Flashloader exposing a CCSDS interface via UART](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/flashloader) use core::{convert::Infallible, ops::Deref}; use fugit::RateExtU32; -use vorago_shared_periphs::{gpio::Pin, FunSel, InterruptConfig}; +use vorago_shared_periphs::{ + gpio::{IoPeriphPin, Pin}, + FunSel, InterruptConfig, +}; use crate::{ clock::enable_peripheral_clock, @@ -22,7 +25,7 @@ use crate::{ pac::{self, uarta as uart_base}, pins::{ Pa16, Pa17, Pa18, Pa19, Pa2, Pa26, Pa27, Pa3, Pa30, Pa31, Pa8, Pa9, Pb18, Pb19, Pb20, Pb21, - Pb22, Pb23, Pb6, Pb7, Pb8, Pb9, + Pb22, Pb23, Pb6, Pb7, Pb8, Pb9, PinMarker, }, time::Hertz, PeripheralSelect, @@ -55,11 +58,11 @@ impl UartId { // Type-Level support //================================================================================================== -pub trait TxPin { +pub trait TxPin: PinMarker { const UART_ID: UartId; const FUN_SEL: FunSel; } -pub trait RxPin { +pub trait RxPin: PinMarker { const UART_ID: UartId; const FUN_SEL: FunSel; } @@ -557,6 +560,8 @@ impl Uart { if UartI::ID != TxPinI::UART_ID || UartI::ID != RxPinI::UART_ID { return Err(UartIdMissmatchError); } + IoPeriphPin::new(TxPinI::ID, TxPinI::FUN_SEL, None); + IoPeriphPin::new(RxPinI::ID, TxPinI::FUN_SEL, None); crate::clock::enable_peripheral_clock(UartI::PERIPH_SEL); let reg_block = unsafe { UartI::reg_block() }; diff --git a/va108xx-hal/src/uart/rx_asynch.rs b/va108xx-hal/src/uart/rx_asynch.rs index 78857a0..34f0c65 100644 --- a/va108xx-hal/src/uart/rx_asynch.rs +++ b/va108xx-hal/src/uart/rx_asynch.rs @@ -411,10 +411,10 @@ impl embedded_io_async::Read for RxAsyncOverwriting { critical_section::with(|cs| { let queue = inner.shared_consumer.borrow(cs); if queue.borrow().as_ref().unwrap().len() == 0 { - RX_HAS_DATA[id as usize].store(false, Ordering::Relaxed); + RX_HAS_DATA[id].store(false, Ordering::Relaxed); } }); - let _guard = ActiveReadGuard(id as usize); + let _guard = ActiveReadGuard(id); let mut handle_data_in_queue = |inner: &mut RxAsyncOverwritingInner| { critical_section::with(|cs| { let mut consumer_ref = inner.shared_consumer.borrow(cs).borrow_mut(); diff --git a/vorago-reb1/Cargo.toml b/vorago-reb1/Cargo.toml index ff242e0..c32c151 100644 --- a/vorago-reb1/Cargo.toml +++ b/vorago-reb1/Cargo.toml @@ -15,10 +15,11 @@ cortex-m = { version = "0.7", features = ["critical-section-single-core"] } cortex-m-rt = "0.7" embedded-hal = "1" nb = "1" -bitfield = ">=0.17, <=0.19" +bitbybit = "1.3" +arbitrary-int = "1.3" max116xx-10bit = "0.3" -va108xx-hal = { version = ">=0.10, <=0.11", features = ["rt"] } +va108xx-hal = { version = ">=0.10, <=0.11", path = "../va108xx-hal", features = ["rt"] } [features] rt = ["va108xx-hal/rt"] diff --git a/vorago-reb1/examples/adt75-temp-sensor.rs b/vorago-reb1/examples/adt75-temp-sensor.rs index 40187bd..ad29bc7 100644 --- a/vorago-reb1/examples/adt75-temp-sensor.rs +++ b/vorago-reb1/examples/adt75-temp-sensor.rs @@ -4,16 +4,16 @@ use cortex_m_rt::entry; use embedded_hal::delay::DelayNs; use panic_rtt_target as _; use rtt_target::{rprintln, rtt_init_print}; -use va108xx_hal::{pac, prelude::*, timer::set_up_ms_delay_provider}; +use va108xx_hal::{pac, prelude::*, timer::CountdownTimer}; use vorago_reb1::temp_sensor::Adt75TempSensor; #[entry] fn main() -> ! { rtt_init_print!(); rprintln!("-- Vorago Temperature Sensor and I2C Example --"); - let mut dp = pac::Peripherals::take().unwrap(); - let mut delay = set_up_ms_delay_provider(&mut dp.sysconfig, 50.MHz(), dp.tim0); - let mut temp_sensor = Adt75TempSensor::new(&mut dp.sysconfig, 50.MHz(), dp.i2ca) + let dp = pac::Peripherals::take().unwrap(); + let mut delay = CountdownTimer::new(50.MHz(), dp.tim0); + let mut temp_sensor = Adt75TempSensor::new(50.MHz(), dp.i2ca) .expect("Creating temperature sensor struct failed"); loop { let temp = temp_sensor diff --git a/vorago-reb1/examples/adxl343-accelerometer.rs b/vorago-reb1/examples/adxl343-accelerometer.rs index ce7be6c..9fccc30 100644 --- a/vorago-reb1/examples/adxl343-accelerometer.rs +++ b/vorago-reb1/examples/adxl343-accelerometer.rs @@ -9,13 +9,14 @@ use embedded_hal::delay::DelayNs; use embedded_hal::spi::{SpiBus, MODE_3}; use panic_rtt_target as _; use rtt_target::{rprintln, rtt_init_print}; -use va108xx_hal::spi::SpiClkConfig; +use va108xx_hal::gpio::{Output, PinState}; +use va108xx_hal::pins::PinsA; +use va108xx_hal::spi::{configure_pin_as_hw_cs_pin, SpiClkConfig}; +use va108xx_hal::timer::CountdownTimer; use va108xx_hal::{ - gpio::PinsA, pac, prelude::*, spi::{Spi, SpiConfig}, - timer::set_up_ms_delay_provider, }; const READ_MASK: u8 = 1 << 7; @@ -29,19 +30,19 @@ const PWR_MEASUREMENT_MODE_MASK: u8 = 1 << 3; fn main() -> ! { rtt_init_print!(); rprintln!("-- Vorago Accelerometer Example --"); - let mut dp = pac::Peripherals::take().unwrap(); - let mut delay = set_up_ms_delay_provider(&mut dp.sysconfig, 50.MHz(), dp.tim0); - let pinsa = PinsA::new(&mut dp.sysconfig, dp.porta); + let dp = pac::Peripherals::take().unwrap(); + let pinsa = PinsA::new(dp.porta); + let mut delay = CountdownTimer::new(50.MHz(), dp.tim0); let (sck, mosi, miso) = ( - pinsa.pa20.into_funsel_2(), - pinsa.pa19.into_funsel_2(), - pinsa.pa18.into_funsel_2(), + pinsa.pa20, + pinsa.pa19, + pinsa.pa18, ); - let cs_pin = pinsa.pa16.into_funsel_2(); + let cs_pin = pinsa.pa16; + let hw_cs_id = configure_pin_as_hw_cs_pin(cs_pin); // Need to set the ADC chip select low - let mut adc_cs = pinsa.pa17.into_push_pull_output(); - adc_cs.set_high(); + Output::new(pinsa.pa17, PinState::Low); let spi_cfg = SpiConfig::default() .clk_cfg( @@ -50,13 +51,12 @@ fn main() -> ! { .mode(MODE_3) .slave_output_disable(true); let mut spi = Spi::new( - &mut dp.sysconfig, 50.MHz(), dp.spib, (sck, miso, mosi), spi_cfg, - ); - spi.cfg_hw_cs_with_pin(&cs_pin); + ).unwrap(); + spi.cfg_hw_cs(hw_cs_id); let mut tx_rx_buf: [u8; 3] = [0; 3]; tx_rx_buf[0] = READ_MASK | DEVID_REG; diff --git a/vorago-reb1/examples/blinky-button-irq.rs b/vorago-reb1/examples/blinky-button-irq.rs index bc113fc..36fac07 100644 --- a/vorago-reb1/examples/blinky-button-irq.rs +++ b/vorago-reb1/examples/blinky-button-irq.rs @@ -10,10 +10,10 @@ use panic_rtt_target as _; use rtt_target::{rprintln, rtt_init_print}; use va108xx_hal::{ clock::{set_clk_div_register, FilterClkSel}, - gpio::{FilterType, InterruptEdge, PinsA}, + gpio::{FilterType, InterruptEdge}, pac::{self, interrupt}, - prelude::*, - timer::{default_ms_irq_handler, set_up_ms_tick, InterruptConfig}, + pins::PinsA, + timer::InterruptConfig, }; use vorago_reb1::button::Button; use vorago_reb1::leds::Leds; @@ -35,18 +35,18 @@ fn main() -> ! { rtt_init_print!(); rprintln!("-- Vorago Button IRQ Example --"); let mut dp = pac::Peripherals::take().unwrap(); - let pinsa = PinsA::new(&mut dp.sysconfig, dp.porta); + let pinsa = PinsA::new(dp.porta); let edge_irq = match PRESS_MODE { PressMode::Toggle => InterruptEdge::HighToLow, PressMode::Keep => InterruptEdge::BothEdges, }; // Configure an edge interrupt on the button and route it to interrupt vector 15 - let mut button = Button::new(pinsa.pa11.into_floating_input()); + let mut button = Button::new(pinsa.pa11); if PRESS_MODE == PressMode::Toggle { // This filter debounces the switch for edge based interrupts - button.configure_filter_type(FilterType::FilterFourClockCycles, FilterClkSel::Clk1); + button.configure_filter_type(FilterType::FilterFourCycles, FilterClkSel::Clk1); set_clk_div_register(&mut dp.sysconfig, FilterClkSel::Clk1, 50_000); } button.configure_and_enable_edge_interrupt( @@ -54,18 +54,7 @@ fn main() -> ! { InterruptConfig::new(pac::interrupt::OC15, true, true), ); - set_up_ms_tick( - InterruptConfig::new(pac::Interrupt::OC0, true, true), - &mut dp.sysconfig, - Some(&mut dp.irqsel), - 50.MHz(), - dp.tim0, - ); - let mut leds = Leds::new( - pinsa.pa10.into_push_pull_output(), - pinsa.pa7.into_push_pull_output(), - pinsa.pa6.into_push_pull_output(), - ); + let mut leds = Leds::new(pinsa.pa10, pinsa.pa7, pinsa.pa6); for led in leds.iter_mut() { led.off(); } @@ -79,11 +68,6 @@ fn main() -> ! { } } -#[interrupt] -fn OC0() { - default_ms_irq_handler(); -} - #[interrupt] fn OC15() { cortex_m::interrupt::free(|cs| { diff --git a/vorago-reb1/examples/blinky-leds.rs b/vorago-reb1/examples/blinky-leds.rs index de9fbd5..b5aea2c 100644 --- a/vorago-reb1/examples/blinky-leds.rs +++ b/vorago-reb1/examples/blinky-leds.rs @@ -9,7 +9,13 @@ use cortex_m_rt::entry; use embedded_hal::delay::DelayNs; use panic_halt as _; -use va108xx_hal::{gpio::PinsA, pac, prelude::*, timer::set_up_ms_delay_provider}; +use va108xx_hal::{ + gpio::{Output, PinState}, + pac, + pins::PinsA, + prelude::*, + timer::CountdownTimer, +}; use vorago_reb1::leds::Leds; // REB LED pin definitions. All on port A @@ -26,7 +32,7 @@ enum LibType { #[entry] fn main() -> ! { - let mut dp = pac::Peripherals::take().unwrap(); + let dp = pac::Peripherals::take().unwrap(); let lib_type = LibType::Bsp; @@ -60,11 +66,11 @@ fn main() -> ! { } } LibType::Hal => { - let pins = PinsA::new(&mut dp.sysconfig, dp.porta); - let mut led1 = pins.pa10.into_readable_push_pull_output(); - let mut led2 = pins.pa7.into_readable_push_pull_output(); - let mut led3 = pins.pa6.into_readable_push_pull_output(); - let mut delay = set_up_ms_delay_provider(&mut dp.sysconfig, 50.MHz(), dp.tim0); + let pins = PinsA::new(dp.porta); + let mut led1 = Output::new(pins.pa10, PinState::Low); + let mut led2 = Output::new(pins.pa7, PinState::Low); + let mut led3 = Output::new(pins.pa6, PinState::Low); + let mut delay = CountdownTimer::new(50.MHz(), dp.tim0); for _ in 0..10 { led1.set_low(); led2.set_low(); @@ -83,13 +89,9 @@ fn main() -> ! { } } LibType::Bsp => { - let pinsa = PinsA::new(&mut dp.sysconfig, dp.porta); - let mut leds = Leds::new( - pinsa.pa10.into_push_pull_output(), - pinsa.pa7.into_push_pull_output(), - pinsa.pa6.into_push_pull_output(), - ); - let mut delay = set_up_ms_delay_provider(&mut dp.sysconfig, 50.MHz(), dp.tim0); + let pinsa = PinsA::new(dp.porta); + let mut leds = Leds::new(pinsa.pa10, pinsa.pa7, pinsa.pa6); + let mut delay = CountdownTimer::new(50.MHz(), dp.tim0); for _ in 0..10 { // Blink all LEDs quickly for led in leds.iter_mut() { diff --git a/vorago-reb1/src/button.rs b/vorago-reb1/src/button.rs index a16ff7f..1d261f7 100644 --- a/vorago-reb1/src/button.rs +++ b/vorago-reb1/src/button.rs @@ -5,16 +5,18 @@ //! - [Button Blinky with IRQs](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/vorago-reb1/examples/blinky-button-irq.rs) //! - [Button Blinky with IRQs and RTIC](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/vorago-reb1/examples/blinky-button-rtic.rs) use va108xx_hal::{ - gpio::{FilterClkSel, FilterType, InputFloating, InterruptEdge, InterruptLevel, Pin, PA11}, + clock::FilterClkSel, + gpio::{FilterType, Input, InterruptEdge, InterruptLevel, Pin}, + pins::Pa11, InterruptConfig, }; #[derive(Debug)] -pub struct Button(pub Pin); +pub struct Button(pub Input); impl Button { - pub fn new(pin: Pin) -> Button { - Button(pin) + pub fn new(pin: Pin) -> Button { + Button(Input::new_floating(pin)) } #[inline] diff --git a/vorago-reb1/src/leds.rs b/vorago-reb1/src/leds.rs index dfa9ec1..560e5a2 100644 --- a/vorago-reb1/src/leds.rs +++ b/vorago-reb1/src/leds.rs @@ -6,20 +6,20 @@ //! - [Button Blinky using IRQs](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/vorago-reb1/examples/blinky-button-irq.rs) //! - [Button Blinky using IRQs and RTIC](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/vorago-reb1/examples/blinky-button-rtic.rs) use va108xx_hal::{ - gpio::dynpin::DynPin, - gpio::pin::{Pin, PushPullOutput, PA10, PA6, PA7}, + gpio::{Output, PinState}, + pins::{Pa10, Pa6, Pa7, Pin}, }; -pub type LD2 = Pin; -pub type LD3 = Pin; -pub type LD4 = Pin; - #[derive(Debug)] pub struct Leds(pub [Led; 3]); impl Leds { - pub fn new(led_pin1: LD2, led_pin2: LD3, led_pin3: LD4) -> Leds { - Leds([led_pin1.into(), led_pin2.into(), led_pin3.into()]) + pub fn new(led_pin1: Pin, led_pin2: Pin, led_pin3: Pin) -> Leds { + Leds([ + Led(Output::new(led_pin1, PinState::Low)), + Led(Output::new(led_pin2, PinState::Low)), + Led(Output::new(led_pin3, PinState::Low)), + ]) } } @@ -52,38 +52,24 @@ impl core::ops::IndexMut for Leds { } #[derive(Debug)] -pub struct Led(pub DynPin); - -macro_rules! ctor { - ($($ldx:ident),+) => { - $( - impl From<$ldx> for Led { - fn from(led: $ldx) -> Self { - Led(led.into()) - } - } - )+ - } -} - -ctor!(LD2, LD3, LD4); +pub struct Led(Output); impl Led { /// Turns the LED off. Setting the pin high actually turns the LED off #[inline] pub fn off(&mut self) { - self.0.set_high().ok(); + self.0.set_high(); } /// Turns the LED on. Setting the pin low actually turns the LED on #[inline] pub fn on(&mut self) { - self.0.set_low().ok(); + self.0.set_low(); } /// Toggles the LED #[inline] pub fn toggle(&mut self) { - self.0.toggle().ok(); + self.0.toggle(); } } diff --git a/vorago-reb1/src/m95m01.rs b/vorago-reb1/src/m95m01.rs index 528b9b3..c83a2ef 100644 --- a/vorago-reb1/src/m95m01.rs +++ b/vorago-reb1/src/m95m01.rs @@ -7,20 +7,25 @@ //! # Example //! //! - [REB1 EEPROM example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/vorago-reb1/examples/nvm.rs) +use arbitrary_int::{u2, u3}; use core::convert::Infallible; use embedded_hal::spi::SpiBus; pub const PAGE_SIZE: usize = 256; -bitfield::bitfield! { - pub struct StatusReg(u8); - impl Debug; - u8; - pub status_register_write_protect, _: 7; - pub zero_segment, _: 6, 4; - pub block_protection_bits, set_block_protection_bits: 3, 2; - pub write_enable_latch, _: 1; - pub write_in_progress, _: 0; +#[bitbybit::bitfield(u8)] +#[derive(Debug)] +pub struct StatusReg { + #[bit(7, r)] + status_register_write_protect: bool, + #[bits(4..=6, r)] + zero_segment: u3, + #[bits(2..=3, rw)] + block_protection_bits: u2, + #[bit(1, r)] + write_enable_latch: bool, + #[bit(0, r)] + write_in_progress: bool, } // Registers. @@ -43,10 +48,10 @@ use regs::*; use va108xx_hal::{ pac, prelude::*, - spi::{RomMiso, RomMosi, RomSck, Spi, SpiClkConfig, SpiConfig, BMSTART_BMSTOP_MASK}, + spi::{Spi, SpiClkConfig, SpiConfig, SpiLowLevel, BMSTART_BMSTOP_MASK}, }; -pub type RomSpi = Spi; +pub type RomSpi = Spi; /// Driver for the ST device M95M01 EEPROM memory. /// @@ -59,14 +64,13 @@ pub struct M95M01 { pub struct PageBoundaryExceededError; impl M95M01 { - pub fn new(syscfg: &mut pac::Sysconfig, sys_clk: impl Into, spi: pac::Spic) -> Self { - let spi = RomSpi::new( - syscfg, + pub fn new(sys_clk: Hertz, spi: pac::Spic) -> Self { + let spi = RomSpi::new_for_rom( sys_clk, spi, - (RomSck, RomMiso, RomMosi), SpiConfig::default().clk_cfg(SpiClkConfig::new(2, 4)), - ); + ) + .unwrap(); let mut spi_dev = Self { spi }; spi_dev.clear_block_protection().unwrap(); spi_dev @@ -74,7 +78,7 @@ impl M95M01 { pub fn release(mut self) -> pac::Spic { self.set_block_protection().unwrap(); - self.spi.release().0 + unsafe { pac::Spic::steal() } } // Wait until the write-in-progress state is cleared. This exposes a [nb] API, so this function @@ -90,7 +94,7 @@ impl M95M01 { pub fn read_status_reg(&mut self) -> Result { let mut write_read: [u8; 2] = [regs::RDSR, 0x00]; self.spi.transfer_in_place(&mut write_read)?; - Ok(StatusReg(write_read[1])) + Ok(StatusReg::new_with_raw_value(write_read[1])) } pub fn write_enable(&mut self) -> Result<(), Infallible> { @@ -104,10 +108,10 @@ impl M95M01 { } pub fn set_block_protection(&mut self) -> Result<(), Infallible> { - let mut reg = StatusReg(0); - reg.set_block_protection_bits(0b11); + let mut reg = StatusReg::new_with_raw_value(0); + reg.set_block_protection_bits(u2::new(0b11)); self.write_enable()?; - self.spi.write(&[WRSR, reg.0]) + self.spi.write(&[WRSR, reg.raw_value()]) } fn common_init_write_and_read(&mut self, address: usize, reg: u8) -> Result<(), Infallible> { diff --git a/vorago-reb1/src/max11619.rs b/vorago-reb1/src/max11619.rs index c4805ed..eb15b82 100644 --- a/vorago-reb1/src/max11619.rs +++ b/vorago-reb1/src/max11619.rs @@ -9,7 +9,7 @@ use max116xx_10bit::{ Error, ExternallyClocked, InternallyClockedInternallyTimedSerialInterface, Max116xx10Bit, Max116xx10BitEocExt, VoltageRefMode, WithWakeupDelay, WithoutWakeupDelay, }; -use va108xx_hal::gpio::{Floating, Input, Pin, PA14}; +use va108xx_hal::gpio::Input; pub type Max11619ExternallyClockedNoWakeup = Max116xx10Bit; @@ -17,7 +17,6 @@ pub type Max11619ExternallyClockedWithWakeup = Max116xx10Bit; pub type Max11619InternallyClocked = Max116xx10BitEocExt; -pub type EocPin = Pin>; pub const AN0_CHANNEL: u8 = 0; pub const AN1_CHANNEL: u8 = 1; @@ -44,9 +43,9 @@ pub fn max11619_externally_clocked_with_wakeup( pub fn max11619_internally_clocked( spi: Spi, - eoc: EocPin, + eoc: Input, v_ref: VoltageRefMode, -) -> Result, Error> { +) -> Result, Error> { let mut adc = Max116xx10Bit::max11619(spi)? .into_int_clkd_int_timed_through_ser_if_without_wakeup(v_ref, eoc)?; adc.reset(false)?; diff --git a/vorago-reb1/src/temp_sensor.rs b/vorago-reb1/src/temp_sensor.rs index 25b20df..23aba34 100644 --- a/vorago-reb1/src/temp_sensor.rs +++ b/vorago-reb1/src/temp_sensor.rs @@ -48,15 +48,10 @@ impl From for AdtInitError { } impl Adt75TempSensor { - pub fn new( - sys_cfg: &mut pac::Sysconfig, - sys_clk: impl Into + Copy, - i2ca: pac::I2ca, - ) -> Result { + pub fn new(sys_clk: Hertz, i2ca: pac::I2ca) -> Result { let mut sensor = Adt75TempSensor { // The master construction can not fail for regular I2C speed. sensor_if: I2cMaster::new( - sys_cfg, sys_clk, i2ca, MasterConfig::default(), diff --git a/vorago-shared-periphs/src/gpio/asynch.rs b/vorago-shared-periphs/src/gpio/asynch.rs index b8ac438..5ba3945 100644 --- a/vorago-shared-periphs/src/gpio/asynch.rs +++ b/vorago-shared-periphs/src/gpio/asynch.rs @@ -102,8 +102,7 @@ impl InputPinFuture { ) -> Self { let (waker_group, edge_detection_group) = Self::pin_group_to_waker_and_edge_detection_group(pin.id().port()); - edge_detection_group[pin.id().offset() as usize] - .store(false, core::sync::atomic::Ordering::Relaxed); + edge_detection_group[pin.id().offset()].store(false, core::sync::atomic::Ordering::Relaxed); pin.configure_edge_interrupt(edge); #[cfg(feature = "vor1x")] pin.enable_interrupt(InterruptConfig::new(irq, true, true)); @@ -128,7 +127,7 @@ impl Future for InputPinFuture { self: core::pin::Pin<&mut Self>, cx: &mut core::task::Context<'_>, ) -> core::task::Poll { - let idx = self.id.offset() as usize; + let idx = self.id.offset(); self.waker_group[idx].register(cx.waker()); if self.edge_detection_group[idx].swap(false, core::sync::atomic::Ordering::Relaxed) { return core::task::Poll::Ready(()); diff --git a/vorago-shared-periphs/src/gpio/ll.rs b/vorago-shared-periphs/src/gpio/ll.rs index 3c24a4c..2c60c10 100644 --- a/vorago-shared-periphs/src/gpio/ll.rs +++ b/vorago-shared-periphs/src/gpio/ll.rs @@ -1,5 +1,7 @@ pub use embedded_hal::digital::PinState; +use crate::ioconfig::FilterClkSel; +use crate::ioconfig::FilterType; #[cfg(feature = "vor1x")] use crate::{PeripheralSelect, sysconfig::enable_peripheral_clock}; @@ -27,15 +29,28 @@ pub enum InterruptLevel { #[cfg_attr(feature = "defmt", derive(defmt::Format))] pub struct PinId { port: Port, - offset: usize, + offset: u8, } impl PinId { + pub const fn new_unchecked(port: Port, offset: usize) -> Self { + if offset >= port.max_offset() { + panic!("Pin ID construction: offset is out of range"); + } + PinId { + port, + offset: offset as u8, + } + } + pub const fn new(port: Port, offset: usize) -> Result { if offset >= port.max_offset() { return Err(InvalidOffsetError { offset, port }); } - Ok(PinId { port, offset }) + Ok(PinId { + port, + offset: offset as u8, + }) } pub const fn port(&self) -> Port { @@ -43,7 +58,7 @@ impl PinId { } pub const fn offset(&self) -> usize { - self.offset + self.offset as usize } } @@ -53,6 +68,15 @@ pub struct LowLevelGpio { id: PinId, } +impl core::fmt::Debug for LowLevelGpio { + fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result { + f.debug_struct("LowLevelGpio") + .field("gpio", &self.gpio.port()) + .field("id", &self.id) + .finish() + } +} + impl LowLevelGpio { pub fn new(id: PinId) -> Self { LowLevelGpio { @@ -78,23 +102,17 @@ impl LowLevelGpio { } pub fn configure_as_input_floating(&mut self) { - unsafe { - self.ioconfig.modify_pin_config_unchecked( - self.id.port(), - self.id.offset(), - |mut config| { - config.set_funsel(FunSel::Sel0); - config.set_io_disable(false); - config.set_invert_input(false); - config.set_open_drain(false); - config.set_pull_enable(false); - config.set_pull_when_output_active(false); - config.set_invert_output(false); - config.set_input_enable_when_output(false); - config - }, - ); - } + self.ioconfig.modify_pin_config(self.id, |mut config| { + config.set_funsel(FunSel::Sel0); + config.set_io_disable(false); + config.set_invert_input(false); + config.set_open_drain(false); + config.set_pull_enable(false); + config.set_pull_when_output_active(false); + config.set_invert_output(false); + config.set_input_enable_when_output(false); + config + }); self.gpio.modify_dir(|mut dir| { dir &= !(1 << self.id.offset()); dir @@ -102,24 +120,18 @@ impl LowLevelGpio { } pub fn configure_as_input_with_pull(&mut self, pull: Pull) { - unsafe { - self.ioconfig.modify_pin_config_unchecked( - self.id.port(), - self.id.offset(), - |mut config| { - config.set_funsel(FunSel::Sel0); - config.set_io_disable(false); - config.set_invert_input(false); - config.set_open_drain(false); - config.set_pull_enable(true); - config.set_pull_dir(pull); - config.set_pull_when_output_active(false); - config.set_invert_output(false); - config.set_input_enable_when_output(false); - config - }, - ); - } + self.ioconfig.modify_pin_config(self.id, |mut config| { + config.set_funsel(FunSel::Sel0); + config.set_io_disable(false); + config.set_invert_input(false); + config.set_open_drain(false); + config.set_pull_enable(true); + config.set_pull_dir(pull); + config.set_pull_when_output_active(false); + config.set_invert_output(false); + config.set_input_enable_when_output(false); + config + }); self.gpio.modify_dir(|mut dir| { dir &= !(1 << self.id.offset()); dir @@ -127,23 +139,17 @@ impl LowLevelGpio { } pub fn configure_as_output_push_pull(&mut self, init_level: PinState) { - unsafe { - self.ioconfig.modify_pin_config_unchecked( - self.id.port(), - self.id.offset(), - |mut config| { - config.set_funsel(FunSel::Sel0); - config.set_io_disable(false); - config.set_invert_input(false); - config.set_open_drain(false); - config.set_pull_enable(false); - config.set_pull_when_output_active(false); - config.set_invert_output(false); - config.set_input_enable_when_output(true); - config - }, - ); - } + self.ioconfig.modify_pin_config(self.id, |mut config| { + config.set_funsel(FunSel::Sel0); + config.set_io_disable(false); + config.set_invert_input(false); + config.set_open_drain(false); + config.set_pull_enable(false); + config.set_pull_when_output_active(false); + config.set_invert_output(false); + config.set_input_enable_when_output(true); + config + }); match init_level { PinState::Low => self.gpio.write_clr_out(self.mask_32()), PinState::High => self.gpio.write_set_out(self.mask_32()), @@ -155,24 +161,18 @@ impl LowLevelGpio { } pub fn configure_as_output_open_drain(&mut self, init_level: PinState) { - unsafe { - self.ioconfig.modify_pin_config_unchecked( - self.id.port(), - self.id.offset(), - |mut config| { - config.set_funsel(FunSel::Sel0); - config.set_io_disable(false); - config.set_invert_input(false); - config.set_open_drain(true); - config.set_pull_enable(true); - config.set_pull_dir(Pull::Up); - config.set_pull_when_output_active(false); - config.set_invert_output(false); - config.set_input_enable_when_output(true); - config - }, - ); - } + self.ioconfig.modify_pin_config(self.id, |mut config| { + config.set_funsel(FunSel::Sel0); + config.set_io_disable(false); + config.set_invert_input(false); + config.set_open_drain(true); + config.set_pull_enable(true); + config.set_pull_dir(Pull::Up); + config.set_pull_when_output_active(false); + config.set_invert_output(false); + config.set_input_enable_when_output(true); + config + }); let mask32 = self.mask_32(); match init_level { PinState::Low => self.gpio.write_clr_out(mask32), @@ -185,22 +185,16 @@ impl LowLevelGpio { } pub fn configure_as_peripheral_pin(&mut self, fun_sel: FunSel, pull: Option) { - unsafe { - self.ioconfig.modify_pin_config_unchecked( - self.id.port(), - self.id.offset(), - |mut config| { - config.set_funsel(fun_sel); - config.set_io_disable(false); - config.set_invert_input(false); - config.set_open_drain(false); - config.set_pull_enable(pull.is_some()); - config.set_pull_dir(pull.unwrap_or(Pull::Up)); - config.set_invert_output(false); - config - }, - ); - } + self.ioconfig.modify_pin_config(self.id, |mut config| { + config.set_funsel(fun_sel); + config.set_io_disable(false); + config.set_invert_input(false); + config.set_open_drain(false); + config.set_pull_enable(pull.is_some()); + config.set_pull_dir(pull.unwrap_or(Pull::Up)); + config.set_invert_output(false); + config + }); } #[inline] @@ -295,6 +289,79 @@ impl LowLevelGpio { } } + /// Configure which edge or level type triggers an interrupt + #[inline] + pub fn configure_level_interrupt(&mut self, level: InterruptLevel) { + let mask32 = self.mask_32(); + self.gpio.modify_irq_sen(|mut value| { + value |= mask32; + value + }); + if level == InterruptLevel::Low { + self.gpio.modify_irq_evt(|mut value| { + value &= !mask32; + value + }); + } else { + self.gpio.modify_irq_evt(|mut value| { + value |= mask32; + value + }); + } + } + + /// Only useful for input pins + #[inline] + pub fn configure_filter_type(&mut self, filter: FilterType, clksel: FilterClkSel) { + self.ioconfig.modify_pin_config(self.id, |mut config| { + config.set_filter_type(filter); + config.set_filter_clk_sel(clksel); + config + }); + } + + /// Only useful for output pins. + #[inline] + pub fn configure_pulse_mode(&mut self, enable: bool, default_state: PinState) { + self.gpio.modify_pulse(|mut value| { + if enable { + value |= 1 << self.id.offset; + } else { + value &= !(1 << self.id.offset); + } + value + }); + self.gpio.modify_pulsebase(|mut value| { + if default_state == PinState::High { + value |= 1 << self.id.offset; + } else { + value &= !(1 << self.id.offset); + } + value + }); + } + + /// Only useful for output pins + #[inline] + pub fn configure_delay(&mut self, delay_1: bool, delay_2: bool) { + self.gpio.modify_delay1(|mut value| { + if delay_1 { + value |= 1 << self.id.offset; + } else { + value &= !(1 << self.id.offset); + } + value + }); + self.gpio.modify_delay2(|mut value| { + if delay_2 { + value |= 1 << self.id.offset; + } else { + value &= !(1 << self.id.offset); + } + value + }); + } + #[cfg(feature = "vor1x")] /// Configure the IRQSEL peripheral for this particular pin with the given interrupt ID. pub fn configure_irqsel(&mut self, id: va108xx::Interrupt) { @@ -304,12 +371,12 @@ impl LowLevelGpio { // Set the correct interrupt number in the IRQSEL register super::Port::A => { irqsel - .porta0(self.id().offset() as usize) + .porta0(self.id().offset()) .write(|w| unsafe { w.bits(id as u32) }); } super::Port::B => { irqsel - .portb0(self.id().offset() as usize) + .portb0(self.id().offset()) .write(|w| unsafe { w.bits(id as u32) }); } } @@ -324,12 +391,12 @@ impl LowLevelGpio { // Set the correct interrupt number in the IRQSEL register super::Port::A => { irqsel - .porta0(self.id().offset() as usize) + .porta0(self.id().offset()) .write(|w| unsafe { w.bits(u32::MAX) }); } super::Port::B => { irqsel - .portb0(self.id().offset() as usize) + .portb0(self.id().offset()) .write(|w| unsafe { w.bits(u32::MAX) }); } } diff --git a/vorago-shared-periphs/src/gpio/mod.rs b/vorago-shared-periphs/src/gpio/mod.rs index c420d70..150c4fc 100644 --- a/vorago-shared-periphs/src/gpio/mod.rs +++ b/vorago-shared-periphs/src/gpio/mod.rs @@ -1,24 +1,22 @@ use core::convert::Infallible; +pub use crate::ioconfig::{FilterClkSel, FilterType, regs::FunSel}; pub use embedded_hal::digital::PinState; -pub use ll::PinId; -pub use ll::{Port, Pull}; - -use crate::ioconfig::regs::FunSel; +pub use ll::{InterruptEdge, InterruptLevel, PinId, Port, Pull}; pub mod asynch; pub mod ll; pub mod regs; -pub trait PinMarker { +pub trait PinIdProvider { const ID: ll::PinId; } -pub struct Pin { +pub struct Pin { phantom: core::marker::PhantomData, } -impl Pin { +impl Pin { #[allow(clippy::new_without_default)] pub const fn new() -> Self { Self { @@ -27,10 +25,11 @@ impl Pin { } } +#[derive(Debug)] pub struct Output(ll::LowLevelGpio); impl Output { - pub fn new(_pin: Pin, init_level: PinState) -> Self { + pub fn new(_pin: Pin, init_level: PinState) -> Self { let mut ll = ll::LowLevelGpio::new(I::ID); ll.configure_as_output_push_pull(init_level); Output(ll) @@ -65,6 +64,12 @@ impl Output { pub fn is_set_low(&self) -> bool { self.0.is_set_low() } + + /// Toggle pin output with dedicated HW feature. + #[inline] + pub fn toggle(&mut self) { + self.0.toggle(); + } } impl embedded_hal::digital::ErrorType for Output { @@ -99,16 +104,17 @@ impl embedded_hal::digital::StatefulOutputPin for Output { } } +#[derive(Debug)] pub struct Input(ll::LowLevelGpio); impl Input { - pub fn new_floating(_pin: Pin) -> Self { + pub fn new_floating(_pin: Pin) -> Self { let mut ll = ll::LowLevelGpio::new(I::ID); ll.configure_as_input_floating(); Input(ll) } - pub fn new_with_pull(_pin: Pin, pull: Pull) -> Self { + pub fn new_with_pull(_pin: Pin, pull: Pull) -> Self { let mut ll = ll::LowLevelGpio::new(I::ID); ll.configure_as_input_with_pull(pull); Input(ll) @@ -126,10 +132,25 @@ impl Input { } #[inline] - pub fn configure_edge_interrupt(&mut self, edge: ll::InterruptEdge) { + pub fn configure_edge_interrupt(&mut self, edge: InterruptEdge) { self.0.configure_edge_interrupt(edge); } + #[inline] + pub fn configure_level_interrupt(&mut self, edge: InterruptLevel) { + self.0.configure_level_interrupt(edge); + } + + #[inline] + pub fn configure_delay(&mut self, delay_1: bool, delay_2: bool) { + self.0.configure_delay(delay_1, delay_2); + } + + #[inline] + pub fn configure_filter_type(&mut self, filter: FilterType, clksel: FilterClkSel) { + self.0.configure_filter_type(filter, clksel); + } + #[inline] pub fn is_low(&self) -> bool { self.0.is_low() @@ -155,6 +176,7 @@ impl embedded_hal::digital::InputPin for Input { } } +#[derive(Debug)] pub enum PinMode { InputFloating, InputWithPull(Pull), @@ -172,13 +194,14 @@ impl PinMode { } } +#[derive(Debug)] pub struct Flex { ll: ll::LowLevelGpio, mode: PinMode, } impl Flex { - pub fn new(_pin: Pin) -> Self { + pub fn new(_pin: Pin) -> Self { let mut ll = ll::LowLevelGpio::new(I::ID); ll.configure_as_input_floating(); Flex { @@ -287,12 +310,22 @@ pub struct IoPeriphPin { } impl IoPeriphPin { - pub fn new(_pin: Pin, fun_sel: FunSel, pull: Option) -> Self { + pub fn new_with_pin( + _pin: Pin, + fun_sel: FunSel, + pull: Option, + ) -> Self { let mut ll = ll::LowLevelGpio::new(I::ID); ll.configure_as_peripheral_pin(fun_sel, pull); IoPeriphPin { ll, fun_sel } } + pub fn new(pin_id: PinId, fun_sel: FunSel, pull: Option) -> Self { + let mut ll = ll::LowLevelGpio::new(pin_id); + ll.configure_as_peripheral_pin(fun_sel, pull); + IoPeriphPin { ll, fun_sel } + } + pub fn port(&self) -> Port { self.ll.port() } diff --git a/vorago-shared-periphs/src/ioconfig/mod.rs b/vorago-shared-periphs/src/ioconfig/mod.rs index 0a86d1c..d5b7d8e 100644 --- a/vorago-shared-periphs/src/ioconfig/mod.rs +++ b/vorago-shared-periphs/src/ioconfig/mod.rs @@ -1 +1,3 @@ +pub use regs::{FilterClkSel, FilterType}; + pub mod regs; diff --git a/vorago-shared-periphs/src/ioconfig/regs.rs b/vorago-shared-periphs/src/ioconfig/regs.rs index 7161fb5..943eb3d 100644 --- a/vorago-shared-periphs/src/ioconfig/regs.rs +++ b/vorago-shared-periphs/src/ioconfig/regs.rs @@ -1,6 +1,6 @@ use core::marker::PhantomData; -use crate::{InvalidOffsetError, NUM_PORT_A, NUM_PORT_B}; +use crate::{NUM_PORT_A, NUM_PORT_B, gpio::PinId}; #[cfg(feature = "vor4x")] use crate::{NUM_PORT_DEFAULT, NUM_PORT_G}; @@ -73,7 +73,7 @@ pub struct Config { #[bit(6, rw)] invert_input: bool, #[bits(3..=5, rw)] - filter_sel: FilterClkSel, + filter_clk_sel: FilterClkSel, #[bits(0..=2, rw)] filter_type: Option, } @@ -134,24 +134,9 @@ impl IoConfig { } impl MmioIoConfig<'_> { - pub fn read_pin_config( - &self, - port: crate::Port, - offset: usize, - ) -> Result { - if offset >= port.max_offset() { - return Err(InvalidOffsetError { port, offset }); - } - Ok(unsafe { self.read_pin_config_unchecked(port, offset) }) - } - - /// This function does NOT perform any bounds checking. - /// - /// # Safety - /// - /// Calling this function with an invalid offset can lead to undefined behaviour. - pub unsafe fn read_pin_config_unchecked(&self, port: crate::Port, offset: usize) -> Config { - match port { + pub fn read_pin_config(&self, id: PinId) -> Config { + let offset = id.offset(); + match id.port() { crate::Port::A => unsafe { self.read_port_a_unchecked(offset) }, crate::Port::B => unsafe { self.read_port_b_unchecked(offset) }, #[cfg(feature = "vor4x")] @@ -167,63 +152,14 @@ impl MmioIoConfig<'_> { } } - pub fn modify_pin_config Config>( - &mut self, - port: crate::Port, - offset: usize, - f: F, - ) -> Result<(), InvalidOffsetError> { - if offset >= port.max_offset() { - return Err(InvalidOffsetError { port, offset }); - } - unsafe { self.modify_pin_config_unchecked(port, offset, f) }; - Ok(()) + pub fn modify_pin_config Config>(&mut self, id: PinId, f: F) { + let config = self.read_pin_config(id); + self.write_pin_config(id, f(config)) } - /// This function does NOT perform any bounds checking. - /// - /// # Safety - /// - /// Calling this function with an invalid offset can lead to undefined behaviour. - pub unsafe fn modify_pin_config_unchecked Config>( - &mut self, - port: crate::Port, - offset: usize, - mut f: F, - ) { - unsafe { - let config = self.read_pin_config_unchecked(port, offset); - self.write_pin_config_unchecked(port, offset, f(config)) - } - } - - pub fn write_pin_config( - &mut self, - port: crate::Port, - offset: usize, - config: Config, - ) -> Result<(), InvalidOffsetError> { - if offset >= port.max_offset() { - return Err(InvalidOffsetError { port, offset }); - } - unsafe { - self.write_pin_config_unchecked(port, offset, config); - } - Ok(()) - } - - /// This function does NOT perform any bounds checking. - /// - /// # Safety - /// - /// Calling this function with an invalid offset can lead to undefined behaviour. - pub unsafe fn write_pin_config_unchecked( - &mut self, - port: crate::Port, - offset: usize, - config: Config, - ) { - match port { + pub fn write_pin_config(&mut self, id: PinId, config: Config) { + let offset = id.offset(); + match id.port() { crate::Port::A => unsafe { self.write_port_a_unchecked(offset, config) }, crate::Port::B => unsafe { self.write_port_b_unchecked(offset, config) }, #[cfg(feature = "vor4x")] diff --git a/vorago-shared-periphs/src/pins.rs b/vorago-shared-periphs/src/pins.rs new file mode 100644 index 0000000..e69de29 diff --git a/vorago-shared-periphs/src/sysconfig.rs b/vorago-shared-periphs/src/sysconfig.rs index 317e503..02054b9 100644 --- a/vorago-shared-periphs/src/sysconfig.rs +++ b/vorago-shared-periphs/src/sysconfig.rs @@ -15,3 +15,29 @@ pub fn disable_peripheral_clock(clock: crate::PeripheralSelect) { .peripheral_clk_enable() .modify(|r, w| unsafe { w.bits(r.bits() & !(1 << clock as u8)) }); } + +#[cfg(feature = "vor1x")] +#[inline] +pub fn assert_peripheral_reset(periph_sel: crate::PeripheralSelect) { + let syscfg = unsafe { va108xx::Sysconfig::steal() }; + syscfg + .peripheral_reset() + .modify(|r, w| unsafe { w.bits(r.bits() & !(1 << periph_sel as u8)) }); +} + +#[cfg(feature = "vor1x")] +#[inline] +pub fn deassert_peripheral_reset(periph_sel: crate::PeripheralSelect) { + let syscfg = unsafe { va108xx::Sysconfig::steal() }; + syscfg + .peripheral_reset() + .modify(|r, w| unsafe { w.bits(r.bits() | (1 << periph_sel as u8)) }); +} + +#[cfg(feature = "vor1x")] +#[inline] +pub fn reset_peripheral_for_cycles(periph_sel: crate::PeripheralSelect, cycles: u32) { + assert_peripheral_reset(periph_sel); + cortex_m::asm::delay(cycles); + deassert_peripheral_reset(periph_sel); +}