From 5c745a09ac069b8c8a5111824631921b87fc07a3 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sun, 23 Jun 2024 21:38:55 +0200 Subject: [PATCH] timer, PWM and I2C module --- examples/simple/Cargo.toml | 4 +- .../examples/{blinky-hal.rs => blinky.rs} | 0 .../simple/examples/peb1-accelerometer.rs | 88 ++ examples/simple/examples/pwm.rs | 81 ++ examples/simple/examples/spi.rs | 2 +- examples/simple/examples/timer-ticks.rs | 68 ++ examples/simple/examples/uart.rs | 2 +- examples/simple/src/lib.rs | 1 + va416xx-hal/Cargo.toml | 4 + va416xx-hal/src/clock.rs | 1 - va416xx-hal/src/i2c.rs | 904 ++++++++++++++++++ va416xx-hal/src/lib.rs | 35 +- va416xx-hal/src/pwm.rs | 388 ++++++++ va416xx-hal/src/spi.rs | 101 +- va416xx-hal/src/timer.rs | 802 ++++++++++++++++ va416xx-hal/src/uart.rs | 172 ++-- va416xx-hal/src/wdt.rs | 12 +- vorago-peb1/Cargo.toml | 13 +- vorago-peb1/src/lib.rs | 49 + vscode/launch.json | 36 + 20 files changed, 2641 insertions(+), 122 deletions(-) rename examples/simple/examples/{blinky-hal.rs => blinky.rs} (100%) create mode 100644 examples/simple/examples/peb1-accelerometer.rs create mode 100644 examples/simple/examples/pwm.rs create mode 100644 examples/simple/examples/timer-ticks.rs create mode 100644 va416xx-hal/src/i2c.rs create mode 100644 va416xx-hal/src/pwm.rs create mode 100644 va416xx-hal/src/timer.rs diff --git a/examples/simple/Cargo.toml b/examples/simple/Cargo.toml index bbad5ea..130ca39 100644 --- a/examples/simple/Cargo.toml +++ b/examples/simple/Cargo.toml @@ -8,9 +8,11 @@ cortex-m-rt = "0.7" va416xx-hal = { path = "../../va416xx-hal" } panic-rtt-target = { version = "0.1.3" } rtt-target = { version = "0.5" } -cortex-m = { version = "0.7", features = ["critical-section-single-core"]} +cortex-m = { version = "0.7", features = ["critical-section-single-core"] } embedded-hal = "1" embedded-hal-nb = "1" nb = "1" embedded-io = "0.6" panic-halt = "0.2" +vorago-peb1 = { path = "../../vorago-peb1" } +accelerometer = "0.12" diff --git a/examples/simple/examples/blinky-hal.rs b/examples/simple/examples/blinky.rs similarity index 100% rename from examples/simple/examples/blinky-hal.rs rename to examples/simple/examples/blinky.rs diff --git a/examples/simple/examples/peb1-accelerometer.rs b/examples/simple/examples/peb1-accelerometer.rs new file mode 100644 index 0000000..a9ed8bf --- /dev/null +++ b/examples/simple/examples/peb1-accelerometer.rs @@ -0,0 +1,88 @@ +//! Example code for the PEB1 development board accelerometer. +#![no_main] +#![no_std] + +use accelerometer::{Accelerometer, RawAccelerometer}; +use cortex_m_rt::entry; +use embedded_hal::delay::DelayNs; +use panic_rtt_target as _; +use rtt_target::{rprintln, rtt_init_print}; +use simple_examples::peb1; +use va416xx_hal::{ + i2c, + pac::{self}, + prelude::*, + pwm::CountdownTimer, +}; +use vorago_peb1::lis2dh12::{self, detect_i2c_addr, FullScale, Odr}; + +pub enum DisplayMode { + Raw, + Normalized, +} + +const DISPLAY_MODE: DisplayMode = DisplayMode::Normalized; + +#[entry] +fn main() -> ! { + rtt_init_print!(); + let mut dp = pac::Peripherals::take().unwrap(); + rprintln!("-- Vorago PEB1 accelerometer example --"); + // Use the external clock connected to XTAL_N. + let clocks = dp + .clkgen + .constrain() + .xtal_n_clk_with_src_freq(peb1::EXTCLK_FREQ) + .freeze(&mut dp.sysconfig) + .unwrap(); + let mut i2c_master = i2c::I2cMaster::new( + dp.i2c0, + &mut dp.sysconfig, + i2c::MasterConfig::default(), + &clocks, + i2c::I2cSpeed::Regular100khz, + ) + .expect("creating I2C master failed"); + let mut delay_provider = CountdownTimer::new(&mut dp.sysconfig, dp.tim1, &clocks); + // Detect the I2C address of the accelerometer by scanning all possible values. + let slave_addr = detect_i2c_addr(&mut i2c_master).expect("detecting I2C address failed"); + // Create the accelerometer driver using the PEB1 BSP. + let mut accelerometer = vorago_peb1::accelerometer::new_with_i2cm(i2c_master, slave_addr) + .expect("creating accelerometer driver failed"); + let device_id = accelerometer.get_device_id().unwrap(); + accelerometer + .set_mode(lis2dh12::reg::Mode::Normal) + .expect("setting mode failed"); + accelerometer + .set_odr(Odr::Hz100) + .expect("setting ODR failed"); + accelerometer + .set_fs(FullScale::G4) + .expect("setting full scale failed"); + // This function also enabled BDU. + accelerometer + .enable_temp(true) + .expect("enabling temperature sensor failed"); + rprintln!("Device ID: 0x{:02X}", device_id); + // Start reading the accelerometer periodically. + loop { + let temperature = accelerometer + .get_temp_outf() + .expect("reading temperature failed"); + match DISPLAY_MODE { + DisplayMode::Normalized => { + let value = accelerometer + .accel_norm() + .expect("reading normalized accelerometer data failed"); + rprintln!("Accel Norm F32x3: {:.06?} | Temp {} °C", value, temperature); + } + DisplayMode::Raw => { + let value_raw = accelerometer + .accel_raw() + .expect("reading raw accelerometer data failed"); + rprintln!("Accel Raw F32x3: {:?} | Temp {} °C", value_raw, temperature); + } + } + delay_provider.delay_ms(100); + } +} diff --git a/examples/simple/examples/pwm.rs b/examples/simple/examples/pwm.rs new file mode 100644 index 0000000..922ae00 --- /dev/null +++ b/examples/simple/examples/pwm.rs @@ -0,0 +1,81 @@ +//! Simple PWM example +#![no_main] +#![no_std] + +use cortex_m_rt::entry; +use embedded_hal::{delay::DelayNs, pwm::SetDutyCycle}; +use panic_rtt_target as _; +use rtt_target::{rprintln, rtt_init_print}; +use simple_examples::peb1; +use va416xx_hal::{ + gpio::PinsA, + pac, + prelude::*, + pwm::{self, get_duty_from_percent, CountdownTimer, PwmA, PwmB, ReducedPwmPin}, +}; + +#[entry] +fn main() -> ! { + rtt_init_print!(); + rprintln!("-- VA108xx PWM example application--"); + let mut dp = pac::Peripherals::take().unwrap(); + + // Use the external clock connected to XTAL_N. + let clocks = dp + .clkgen + .constrain() + .xtal_n_clk_with_src_freq(peb1::EXTCLK_FREQ) + .freeze(&mut dp.sysconfig) + .unwrap(); + + let pinsa = PinsA::new(&mut dp.sysconfig, dp.porta); + let mut pwm = pwm::PwmPin::new( + (pinsa.pa3.into_funsel_1(), dp.tim3), + &mut dp.sysconfig, + &clocks, + 10.Hz(), + ); + let mut delay_timer = CountdownTimer::new(&mut dp.sysconfig, dp.tim0, &clocks); + 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 + while current_duty_cycle < 1.0 { + delay_timer.delay_ms(400); + current_duty_cycle += 0.02; + counter += 1; + if counter % 10 == 0 { + rprintln!("current duty cycle: {}", current_duty_cycle); + } + + reduced_pin + .set_duty_cycle(get_duty_from_percent(current_duty_cycle)) + .unwrap(); + } + + // Switch to PWMB and decrease the window with a high signal from 100 % to 0 % + // continously + 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); + 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 { + delay_timer.delay_ms(400); + lower_limit += 0.01; + upper_limit -= 0.01; + pwmb.set_pwmb_lower_limit(get_duty_from_percent(lower_limit)); + pwmb.set_pwmb_upper_limit(get_duty_from_percent(upper_limit)); + rprintln!("Lower limit: {}", pwmb.pwmb_lower_limit()); + rprintln!("Upper limit: {}", pwmb.pwmb_upper_limit()); + } + reduced_pin = ReducedPwmPin::::from(pwmb); + } +} diff --git a/examples/simple/examples/spi.rs b/examples/simple/examples/spi.rs index 8324249..e9e5401 100644 --- a/examples/simple/examples/spi.rs +++ b/examples/simple/examples/spi.rs @@ -63,7 +63,7 @@ fn main() -> ! { let transfer_cfg = TransferConfig::new_no_hw_cs(SPI_SPEED_KHZ.kHz(), SPI_MODE, BLOCKMODE, false); // Create SPI peripheral. - let mut spi0 = Spi::spi0( + let mut spi0 = Spi::new( dp.spi0, (sck, miso, mosi), &clocks, diff --git a/examples/simple/examples/timer-ticks.rs b/examples/simple/examples/timer-ticks.rs new file mode 100644 index 0000000..4eb47e8 --- /dev/null +++ b/examples/simple/examples/timer-ticks.rs @@ -0,0 +1,68 @@ +//! MS and Second counter implemented using the TIM0 and TIM1 peripheral +#![no_main] +#![no_std] + +use core::cell::Cell; +use cortex_m::interrupt::Mutex; +use cortex_m_rt::entry; +use panic_rtt_target as _; +use rtt_target::{rprintln, rtt_init_print}; +use simple_examples::peb1; +use va416xx_hal::{ + pac::{self, interrupt}, + prelude::*, + timer::{default_ms_irq_handler, set_up_ms_tick, CountdownTimer, MS_COUNTER}, +}; + +#[allow(dead_code)] +enum LibType { + Pac, + Hal, +} + +static SEC_COUNTER: Mutex> = Mutex::new(Cell::new(0)); + +#[entry] +fn main() -> ! { + rtt_init_print!(); + let mut dp = pac::Peripherals::take().unwrap(); + let mut last_ms = 0; + rprintln!("-- Vorago system ticks using timers --"); + // Use the external clock connected to XTAL_N. + let clocks = dp + .clkgen + .constrain() + .xtal_n_clk_with_src_freq(peb1::EXTCLK_FREQ) + .freeze(&mut dp.sysconfig) + .unwrap(); + let _ = set_up_ms_tick(&mut dp.sysconfig, dp.tim0, &clocks); + let mut second_timer = CountdownTimer::new(&mut dp.sysconfig, dp.tim1, &clocks); + second_timer.start(1.Hz()); + second_timer.listen(); + loop { + let current_ms = cortex_m::interrupt::free(|cs| MS_COUNTER.borrow(cs).get()); + if current_ms - last_ms >= 1000 { + last_ms = current_ms; + rprintln!("MS counter: {}", current_ms); + let second = cortex_m::interrupt::free(|cs| SEC_COUNTER.borrow(cs).get()); + rprintln!("Second counter: {}", second); + } + cortex_m::asm::delay(10000); + } +} + +#[interrupt] +#[allow(non_snake_case)] +fn TIM0() { + default_ms_irq_handler() +} + +#[interrupt] +#[allow(non_snake_case)] +fn TIM1() { + cortex_m::interrupt::free(|cs| { + let mut sec = SEC_COUNTER.borrow(cs).get(); + sec += 1; + SEC_COUNTER.borrow(cs).set(sec); + }); +} diff --git a/examples/simple/examples/uart.rs b/examples/simple/examples/uart.rs index ad627ed..0592d73 100644 --- a/examples/simple/examples/uart.rs +++ b/examples/simple/examples/uart.rs @@ -32,7 +32,7 @@ fn main() -> ! { let tx = gpiob.pg0.into_funsel_1(); let rx = gpiob.pg1.into_funsel_1(); - let uart0 = uart::Uart::uart0( + let uart0 = uart::Uart::new( dp.uart0, (tx, rx), Hertz::from_raw(115200), diff --git a/examples/simple/src/lib.rs b/examples/simple/src/lib.rs index cea324a..c5a45f0 100644 --- a/examples/simple/src/lib.rs +++ b/examples/simple/src/lib.rs @@ -1,5 +1,6 @@ #![no_std] +/// PEB1 board specific configuration. pub mod peb1 { use va416xx_hal::time::Hertz; diff --git a/va416xx-hal/Cargo.toml b/va416xx-hal/Cargo.toml index 8f0ffb2..05d99d2 100644 --- a/va416xx-hal/Cargo.toml +++ b/va416xx-hal/Cargo.toml @@ -22,6 +22,10 @@ defmt = { version = "0.3", optional = true } fugit = "0.3" delegate = "0.12" +[dependencies.void] +version = "1" +default-features = false + [dependencies.va416xx] path = "../va416xx" default-features = false diff --git a/va416xx-hal/src/clock.rs b/va416xx-hal/src/clock.rs index c3864d2..adc12eb 100644 --- a/va416xx-hal/src/clock.rs +++ b/va416xx-hal/src/clock.rs @@ -1,5 +1,4 @@ //! This also includes functionality to enable the peripheral clocks -//use va416xx::{, Sysconfig}; use crate::pac; use crate::time::Hertz; diff --git a/va416xx-hal/src/i2c.rs b/va416xx-hal/src/i2c.rs new file mode 100644 index 0000000..ae7b42d --- /dev/null +++ b/va416xx-hal/src/i2c.rs @@ -0,0 +1,904 @@ +//! API for the I2C peripheral +//! +//! ## Examples +//! +//! - [PEB1 accelerometer example](https://egit.irs.uni-stuttgart.de/rust/va416xx-rs/src/branch/main/examples/simple/examples/peb1-accelerometer.rs) +use crate::{ + clock::{ + assert_periph_reset, deassert_periph_reset, enable_peripheral_clock, Clocks, + PeripheralSelect, + }, + pac, + time::Hertz, + typelevel::Sealed, +}; +use core::{marker::PhantomData, ops::Deref}; +use embedded_hal::i2c::{self, Operation, SevenBitAddress, TenBitAddress}; + +//================================================================================================== +// Defintions +//================================================================================================== + +const CLK_100K: Hertz = Hertz::from_raw(100_000); +const CLK_400K: Hertz = Hertz::from_raw(400_000); +const MIN_CLK_400K: Hertz = Hertz::from_raw(10_000_000); + +#[derive(Debug, PartialEq, Eq, Copy, Clone)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +pub enum FifoEmptyMode { + Stall = 0, + EndTransaction = 1, +} + +#[derive(Debug, PartialEq, Eq)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +pub struct ClockTooSlowForFastI2c; + +#[derive(Debug, PartialEq, Eq)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +pub enum Error { + InvalidTimingParams, + ArbitrationLost, + NackAddr, + /// Data not acknowledged in write operation + NackData, + /// Not enough data received in read operation + InsufficientDataReceived, + /// Number of bytes in transfer too large (larger than 0x7fe) + DataTooLarge, +} + +#[derive(Debug, PartialEq, Eq)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +pub enum InitError { + /// Wrong address used in constructor + WrongAddrMode, + /// APB1 clock is too slow for fast I2C mode. + ClkTooSlow(ClockTooSlowForFastI2c), +} + +impl From for InitError { + fn from(value: ClockTooSlowForFastI2c) -> Self { + Self::ClkTooSlow(value) + } +} + +impl embedded_hal::i2c::Error for Error { + fn kind(&self) -> embedded_hal::i2c::ErrorKind { + match self { + Error::ArbitrationLost => embedded_hal::i2c::ErrorKind::ArbitrationLoss, + Error::NackAddr => { + embedded_hal::i2c::ErrorKind::NoAcknowledge(i2c::NoAcknowledgeSource::Address) + } + Error::NackData => { + embedded_hal::i2c::ErrorKind::NoAcknowledge(i2c::NoAcknowledgeSource::Data) + } + Error::DataTooLarge | Error::InsufficientDataReceived | Error::InvalidTimingParams => { + embedded_hal::i2c::ErrorKind::Other + } + } + } +} + +#[derive(Debug, PartialEq, Copy, Clone)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +enum I2cCmd { + Start = 0b00, + Stop = 0b10, + StartWithStop = 0b11, + Cancel = 0b100, +} + +#[derive(Debug, PartialEq, Eq, Copy, Clone)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +pub enum I2cSpeed { + Regular100khz = 0, + Fast400khz = 1, +} + +#[derive(Debug, PartialEq, Eq)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +pub enum I2cDirection { + Send = 0, + Read = 1, +} + +#[derive(Debug, PartialEq, Eq, Copy, Clone)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +pub enum I2cAddress { + Regular(u8), + TenBit(u16), +} + +pub type I2cRegBlock = pac::i2c0::RegisterBlock; + +/// Common trait implemented by all PAC peripheral access structures. The register block +/// format is the same for all SPI blocks. +pub trait Instance: Deref { + const IDX: u8; + const PERIPH_SEL: PeripheralSelect; + + fn ptr() -> *const I2cRegBlock; +} + +impl Instance for pac::I2c0 { + const IDX: u8 = 0; + const PERIPH_SEL: PeripheralSelect = PeripheralSelect::I2c0; + + fn ptr() -> *const I2cRegBlock { + Self::ptr() + } +} + +impl Instance for pac::I2c1 { + const IDX: u8 = 1; + const PERIPH_SEL: PeripheralSelect = PeripheralSelect::I2c1; + + fn ptr() -> *const I2cRegBlock { + Self::ptr() + } +} + +impl Instance for pac::I2c2 { + const IDX: u8 = 2; + const PERIPH_SEL: PeripheralSelect = PeripheralSelect::I2c2; + + fn ptr() -> *const I2cRegBlock { + Self::ptr() + } +} + +//================================================================================================== +// Config +//================================================================================================== + +pub struct TrTfThighTlow(u8, u8, u8, u8); +pub struct TsuStoTsuStaThdStaTBuf(u8, u8, u8, u8); + +pub struct TimingCfg { + // 4 bit max width + tr: u8, + // 4 bit max width + tf: u8, + // 4 bit max width + thigh: u8, + // 4 bit max width + tlow: u8, + // 4 bit max width + tsu_sto: u8, + // 4 bit max width + tsu_sta: u8, + // 4 bit max width + thd_sta: u8, + // 4 bit max width + tbuf: u8, +} + +impl TimingCfg { + pub fn new( + first_16_bits: TrTfThighTlow, + second_16_bits: TsuStoTsuStaThdStaTBuf, + ) -> Result { + if first_16_bits.0 > 0xf + || first_16_bits.1 > 0xf + || first_16_bits.2 > 0xf + || first_16_bits.3 > 0xf + || second_16_bits.0 > 0xf + || second_16_bits.1 > 0xf + || second_16_bits.2 > 0xf + || second_16_bits.3 > 0xf + { + return Err(Error::InvalidTimingParams); + } + Ok(TimingCfg { + tr: first_16_bits.0, + tf: first_16_bits.1, + thigh: first_16_bits.2, + tlow: first_16_bits.3, + tsu_sto: second_16_bits.0, + tsu_sta: second_16_bits.1, + thd_sta: second_16_bits.2, + tbuf: second_16_bits.3, + }) + } + + pub fn reg(&self) -> u32 { + (self.tbuf as u32) << 28 + | (self.thd_sta as u32) << 24 + | (self.tsu_sta as u32) << 20 + | (self.tsu_sto as u32) << 16 + | (self.tlow as u32) << 12 + | (self.thigh as u32) << 8 + | (self.tf as u32) << 4 + | (self.tr as u32) + } +} + +impl Default for TimingCfg { + fn default() -> Self { + TimingCfg { + tr: 0x02, + tf: 0x01, + thigh: 0x08, + tlow: 0x09, + tsu_sto: 0x8, + tsu_sta: 0x0a, + thd_sta: 0x8, + tbuf: 0xa, + } + } +} + +pub struct MasterConfig { + pub tx_fe_mode: FifoEmptyMode, + pub rx_fe_mode: FifoEmptyMode, + /// Enable the analog delay glitch filter + pub alg_filt: bool, + /// Enable the digital glitch filter + pub dlg_filt: bool, + pub tm_cfg: Option, + // Loopback mode + // lbm: bool, +} + +impl Default for MasterConfig { + fn default() -> Self { + MasterConfig { + tx_fe_mode: FifoEmptyMode::Stall, + rx_fe_mode: FifoEmptyMode::Stall, + alg_filt: false, + dlg_filt: false, + tm_cfg: None, + } + } +} + +impl Sealed for MasterConfig {} + +pub struct SlaveConfig { + pub tx_fe_mode: FifoEmptyMode, + pub rx_fe_mode: FifoEmptyMode, + /// Maximum number of words before issuing a negative acknowledge. + /// Range should be 0 to 0x7fe. Setting the value to 0x7ff has the same effect as not setting + /// the enable bit since RXCOUNT stops counting at 0x7fe. + pub max_words: Option, + /// A received address is compared to the ADDRESS register (addr) using the address mask + /// (addr_mask). Those bits with a 1 in the address mask must match for there to be an address + /// match + pub addr: I2cAddress, + /// The default address mask will be 0x3ff to only allow full matches + pub addr_mask: Option, + /// Optionally specify a second I2C address the slave interface responds to + pub addr_b: Option, + pub addr_b_mask: Option, +} + +impl SlaveConfig { + /// Build a default slave config given a specified slave address to respond to + pub fn new(addr: I2cAddress) -> Self { + SlaveConfig { + tx_fe_mode: FifoEmptyMode::Stall, + rx_fe_mode: FifoEmptyMode::Stall, + max_words: None, + addr, + addr_mask: None, + addr_b: None, + addr_b_mask: None, + } + } +} + +impl Sealed for SlaveConfig {} + +//================================================================================================== +// I2C Base +//================================================================================================== + +pub struct I2cBase { + i2c: I2c, + clock: Hertz, +} + +impl I2cBase { + #[inline] + fn unwrap_addr(addr: I2cAddress) -> (u16, u32) { + match addr { + I2cAddress::Regular(addr) => (addr as u16, 0 << 15), + I2cAddress::TenBit(addr) => (addr, 1 << 15), + } + } +} + +impl I2cBase { + pub fn new( + i2c: I2c, + sys_cfg: &mut pac::Sysconfig, + clocks: &Clocks, + speed_mode: I2cSpeed, + ms_cfg: Option<&MasterConfig>, + sl_cfg: Option<&SlaveConfig>, + ) -> Result { + enable_peripheral_clock(sys_cfg, I2c::PERIPH_SEL); + assert_periph_reset(sys_cfg, I2c::PERIPH_SEL); + cortex_m::asm::nop(); + cortex_m::asm::nop(); + deassert_periph_reset(sys_cfg, I2c::PERIPH_SEL); + + let mut i2c_base = I2cBase { + i2c, + clock: clocks.apb1(), + }; + if let Some(ms_cfg) = ms_cfg { + i2c_base.cfg_master(ms_cfg); + } + + if let Some(sl_cfg) = sl_cfg { + i2c_base.cfg_slave(sl_cfg); + } + i2c_base.cfg_clk_scale(speed_mode)?; + Ok(i2c_base) + } + + fn cfg_master(&mut self, ms_cfg: &MasterConfig) { + let (txfemd, rxfemd) = match (ms_cfg.tx_fe_mode, ms_cfg.rx_fe_mode) { + (FifoEmptyMode::Stall, FifoEmptyMode::Stall) => (false, false), + (FifoEmptyMode::Stall, FifoEmptyMode::EndTransaction) => (false, true), + (FifoEmptyMode::EndTransaction, FifoEmptyMode::Stall) => (true, false), + (FifoEmptyMode::EndTransaction, FifoEmptyMode::EndTransaction) => (true, true), + }; + self.i2c.ctrl().modify(|_, w| { + w.txfemd().bit(txfemd); + w.rxffmd().bit(rxfemd); + w.dlgfilter().bit(ms_cfg.dlg_filt); + w.algfilter().bit(ms_cfg.alg_filt) + }); + if let Some(ref tm_cfg) = ms_cfg.tm_cfg { + self.i2c + .tmconfig() + .write(|w| unsafe { w.bits(tm_cfg.reg()) }); + } + self.i2c.fifo_clr().write(|w| { + w.rxfifo().set_bit(); + w.txfifo().set_bit() + }); + } + + fn cfg_slave(&mut self, sl_cfg: &SlaveConfig) { + let (txfemd, rxfemd) = match (sl_cfg.tx_fe_mode, sl_cfg.rx_fe_mode) { + (FifoEmptyMode::Stall, FifoEmptyMode::Stall) => (false, false), + (FifoEmptyMode::Stall, FifoEmptyMode::EndTransaction) => (false, true), + (FifoEmptyMode::EndTransaction, FifoEmptyMode::Stall) => (true, false), + (FifoEmptyMode::EndTransaction, FifoEmptyMode::EndTransaction) => (true, true), + }; + self.i2c.s0_ctrl().modify(|_, w| { + w.txfemd().bit(txfemd); + w.rxffmd().bit(rxfemd) + }); + self.i2c.s0_fifo_clr().write(|w| { + w.rxfifo().set_bit(); + w.txfifo().set_bit() + }); + let max_words = sl_cfg.max_words; + if let Some(max_words) = max_words { + self.i2c + .s0_maxwords() + .write(|w| unsafe { w.bits(1 << 31 | max_words as u32) }); + } + let (addr, addr_mode_mask) = Self::unwrap_addr(sl_cfg.addr); + // The first bit is the read/write value. Normally, both read and write are matched + // using the RWMASK bit of the address mask register + self.i2c + .s0_address() + .write(|w| unsafe { w.bits((addr << 1) as u32 | addr_mode_mask) }); + if let Some(addr_mask) = sl_cfg.addr_mask { + self.i2c + .s0_addressmask() + .write(|w| unsafe { w.bits((addr_mask << 1) as u32) }); + } + if let Some(addr_b) = sl_cfg.addr_b { + let (addr, addr_mode_mask) = Self::unwrap_addr(addr_b); + self.i2c + .s0_addressb() + .write(|w| unsafe { w.bits((addr << 1) as u32 | addr_mode_mask) }) + } + if let Some(addr_b_mask) = sl_cfg.addr_b_mask { + self.i2c + .s0_addressmaskb() + .write(|w| unsafe { w.bits((addr_b_mask << 1) as u32) }) + } + } + + #[inline] + pub fn filters(&mut self, digital_filt: bool, analog_filt: bool) { + self.i2c.ctrl().modify(|_, w| { + w.dlgfilter().bit(digital_filt); + w.algfilter().bit(analog_filt) + }); + } + + #[inline] + pub fn fifo_empty_mode(&mut self, rx: FifoEmptyMode, tx: FifoEmptyMode) { + self.i2c.ctrl().modify(|_, w| { + w.txfemd().bit(tx as u8 != 0); + w.rxffmd().bit(rx as u8 != 0) + }); + } + + fn calc_clk_div(&self, speed_mode: I2cSpeed) -> Result { + if speed_mode == I2cSpeed::Regular100khz { + Ok(((self.clock.raw() / CLK_100K.raw() / 20) - 1) as u8) + } else { + if self.clock.raw() < MIN_CLK_400K.raw() { + return Err(ClockTooSlowForFastI2c); + } + Ok(((self.clock.raw() / CLK_400K.raw() / 25) - 1) as u8) + } + } + + /// Configures the clock scale for a given speed mode setting + pub fn cfg_clk_scale(&mut self, speed_mode: I2cSpeed) -> Result<(), ClockTooSlowForFastI2c> { + let clk_div = self.calc_clk_div(speed_mode)?; + self.i2c + .clkscale() + .write(|w| unsafe { w.bits((speed_mode as u32) << 31 | clk_div as u32) }); + Ok(()) + } + + pub fn load_address(&mut self, addr: u16) { + // Load address + self.i2c + .address() + .write(|w| unsafe { w.bits((addr << 1) as u32) }); + } + + #[inline] + fn stop_cmd(&mut self) { + self.i2c + .cmd() + .write(|w| unsafe { w.bits(I2cCmd::Stop as u32) }); + } +} + +//================================================================================================== +// I2C Master +//================================================================================================== + +pub struct I2cMaster { + i2c_base: I2cBase, + addr: PhantomData, +} + +impl I2cMaster { + pub fn new( + i2c: I2c, + sys_cfg: &mut pac::Sysconfig, + cfg: MasterConfig, + clocks: &Clocks, + speed_mode: I2cSpeed, + ) -> Result { + Ok(I2cMaster { + i2c_base: I2cBase::new(i2c, sys_cfg, clocks, speed_mode, Some(&cfg), None)?, + addr: PhantomData, + } + .enable_master()) + } + + #[inline] + pub fn cancel_transfer(&self) { + self.i2c_base + .i2c + .cmd() + .write(|w| unsafe { w.bits(I2cCmd::Cancel as u32) }); + } + + #[inline] + pub fn clear_tx_fifo(&self) { + self.i2c_base.i2c.fifo_clr().write(|w| w.txfifo().set_bit()); + } + + #[inline] + pub fn clear_rx_fifo(&self) { + self.i2c_base.i2c.fifo_clr().write(|w| w.rxfifo().set_bit()); + } + + #[inline] + pub fn enable_master(self) -> Self { + self.i2c_base.i2c.ctrl().modify(|_, w| w.enable().set_bit()); + self + } + + #[inline] + pub fn disable_master(self) -> Self { + self.i2c_base + .i2c + .ctrl() + .modify(|_, w| w.enable().clear_bit()); + self + } + + #[inline(always)] + fn load_fifo(&self, word: u8) { + self.i2c_base + .i2c + .data() + .write(|w| unsafe { w.bits(word as u32) }); + } + + #[inline(always)] + fn read_fifo(&self) -> u8 { + self.i2c_base.i2c.data().read().bits() as u8 + } + + fn error_handler_write(&mut self, init_cmd: &I2cCmd) { + self.clear_tx_fifo(); + if *init_cmd == I2cCmd::Start { + self.i2c_base.stop_cmd() + } + } + + fn write_base( + &mut self, + addr: I2cAddress, + init_cmd: I2cCmd, + bytes: impl IntoIterator, + ) -> Result<(), Error> { + let mut iter = bytes.into_iter(); + // Load address + let (addr, addr_mode_bit) = I2cBase::::unwrap_addr(addr); + self.i2c_base.i2c.address().write(|w| unsafe { + w.bits(I2cDirection::Send as u32 | (addr << 1) as u32 | addr_mode_bit) + }); + + self.i2c_base + .i2c + .cmd() + .write(|w| unsafe { w.bits(init_cmd as u32) }); + let mut load_if_next_available = || { + if let Some(next_byte) = iter.next() { + self.load_fifo(next_byte); + } + }; + loop { + let status_reader = self.i2c_base.i2c.status().read(); + if status_reader.arblost().bit_is_set() { + self.error_handler_write(&init_cmd); + return Err(Error::ArbitrationLost); + } else if status_reader.nackaddr().bit_is_set() { + self.error_handler_write(&init_cmd); + return Err(Error::NackAddr); + } else if status_reader.nackdata().bit_is_set() { + self.error_handler_write(&init_cmd); + return Err(Error::NackData); + } else if status_reader.idle().bit_is_set() { + return Ok(()); + } else { + while !status_reader.txnfull().bit_is_set() { + load_if_next_available(); + } + } + } + } + + fn write_from_buffer( + &mut self, + init_cmd: I2cCmd, + addr: I2cAddress, + output: &[u8], + ) -> Result<(), Error> { + let len = output.len(); + // It should theoretically possible to transfer larger data sizes by tracking + // the number of sent words and setting it to 0x7fe as soon as only that many + // bytes are remaining. However, large transfer like this are not common. This + // feature will therefore not be supported for now. + if len > 0x7fe { + return Err(Error::DataTooLarge); + } + // Load number of words + self.i2c_base + .i2c + .words() + .write(|w| unsafe { w.bits(len as u32) }); + let mut bytes = output.iter(); + // FIFO has a depth of 16. We load slightly above the trigger level + // but not all of it because the transaction might fail immediately + const FILL_DEPTH: usize = 12; + + // load the FIFO + for _ in 0..core::cmp::min(FILL_DEPTH, len) { + self.load_fifo(*bytes.next().unwrap()); + } + + self.write_base(addr, init_cmd, output.iter().cloned()) + } + + fn read_internal(&mut self, addr: I2cAddress, buffer: &mut [u8]) -> Result<(), Error> { + let len = buffer.len(); + // It should theoretically possible to transfer larger data sizes by tracking + // the number of sent words and setting it to 0x7fe as soon as only that many + // bytes are remaining. However, large transfer like this are not common. This + // feature will therefore not be supported for now. + if len > 0x7fe { + return Err(Error::DataTooLarge); + } + // Clear the receive FIFO + self.clear_rx_fifo(); + + // Load number of words + self.i2c_base + .i2c + .words() + .write(|w| unsafe { w.bits(len as u32) }); + let (addr, addr_mode_bit) = match addr { + I2cAddress::Regular(addr) => (addr as u16, 0 << 15), + I2cAddress::TenBit(addr) => (addr, 1 << 15), + }; + // Load address + self.i2c_base.i2c.address().write(|w| unsafe { + w.bits(I2cDirection::Read as u32 | (addr << 1) as u32 | addr_mode_bit) + }); + + let mut buf_iter = buffer.iter_mut(); + let mut read_bytes = 0; + // Start receive transfer + self.i2c_base + .i2c + .cmd() + .write(|w| unsafe { w.bits(I2cCmd::StartWithStop as u32) }); + let mut read_if_next_available = || { + if let Some(next_byte) = buf_iter.next() { + *next_byte = self.read_fifo(); + } + }; + loop { + let status_reader = self.i2c_base.i2c.status().read(); + if status_reader.arblost().bit_is_set() { + self.clear_rx_fifo(); + return Err(Error::ArbitrationLost); + } else if status_reader.nackaddr().bit_is_set() { + self.clear_rx_fifo(); + return Err(Error::NackAddr); + } else if status_reader.idle().bit_is_set() { + if read_bytes != len { + return Err(Error::InsufficientDataReceived); + } + return Ok(()); + } else if status_reader.rxnempty().bit_is_set() { + read_if_next_available(); + read_bytes += 1; + } + } + } +} + +//====================================================================================== +// Embedded HAL I2C implementations +//====================================================================================== + +impl embedded_hal::i2c::ErrorType for I2cMaster { + type Error = Error; +} + +impl embedded_hal::i2c::I2c for I2cMaster { + fn transaction( + &mut self, + address: SevenBitAddress, + operations: &mut [Operation<'_>], + ) -> Result<(), Self::Error> { + for operation in operations { + match operation { + Operation::Read(buf) => self.read_internal(I2cAddress::Regular(address), buf)?, + Operation::Write(buf) => self.write_from_buffer( + I2cCmd::StartWithStop, + I2cAddress::Regular(address), + buf, + )?, + } + } + Ok(()) + } +} + +impl embedded_hal::i2c::ErrorType for I2cMaster { + type Error = Error; +} + +impl embedded_hal::i2c::I2c for I2cMaster { + fn transaction( + &mut self, + address: TenBitAddress, + operations: &mut [Operation<'_>], + ) -> Result<(), Self::Error> { + for operation in operations { + match operation { + Operation::Read(buf) => self.read_internal(I2cAddress::TenBit(address), buf)?, + Operation::Write(buf) => { + self.write_from_buffer(I2cCmd::StartWithStop, I2cAddress::TenBit(address), buf)? + } + } + } + Ok(()) + } +} + +//================================================================================================== +// I2C Slave +//================================================================================================== + +pub struct I2cSlave { + i2c_base: I2cBase, + addr: PhantomData, +} + +impl I2cSlave { + fn new_generic( + i2c: I2c, + sys_cfg: &mut pac::Sysconfig, + cfg: SlaveConfig, + clocks: &Clocks, + speed_mode: I2cSpeed, + ) -> Result { + Ok(I2cSlave { + i2c_base: I2cBase::new(i2c, sys_cfg, clocks, speed_mode, None, Some(&cfg))?, + addr: PhantomData, + } + .enable_slave()) + } + + #[inline] + pub fn enable_slave(self) -> Self { + self.i2c_base + .i2c + .s0_ctrl() + .modify(|_, w| w.enable().set_bit()); + self + } + + #[inline] + pub fn disable_slave(self) -> Self { + self.i2c_base + .i2c + .s0_ctrl() + .modify(|_, w| w.enable().clear_bit()); + self + } + + #[inline(always)] + fn load_fifo(&self, word: u8) { + self.i2c_base + .i2c + .s0_data() + .write(|w| unsafe { w.bits(word as u32) }); + } + + #[inline(always)] + fn read_fifo(&self) -> u8 { + self.i2c_base.i2c.s0_data().read().bits() as u8 + } + + #[inline] + fn clear_tx_fifo(&self) { + self.i2c_base + .i2c + .s0_fifo_clr() + .write(|w| w.txfifo().set_bit()); + } + + #[inline] + fn clear_rx_fifo(&self) { + self.i2c_base + .i2c + .s0_fifo_clr() + .write(|w| w.rxfifo().set_bit()); + } + + /// Get the last address that was matched by the slave control and the corresponding + /// master direction + pub fn last_address(&self) -> (I2cDirection, u32) { + let bits = self.i2c_base.i2c.s0_lastaddress().read().bits(); + match bits & 0x01 { + 0 => (I2cDirection::Send, bits >> 1), + 1 => (I2cDirection::Read, bits >> 1), + _ => (I2cDirection::Send, bits >> 1), + } + } + + pub fn write(&mut self, output: &[u8]) -> Result<(), Error> { + let len = output.len(); + // It should theoretically possible to transfer larger data sizes by tracking + // the number of sent words and setting it to 0x7fe as soon as only that many + // bytes are remaining. However, large transfer like this are not common. This + // feature will therefore not be supported for now. + if len > 0x7fe { + return Err(Error::DataTooLarge); + } + let mut bytes = output.iter(); + // FIFO has a depth of 16. We load slightly above the trigger level + // but not all of it because the transaction might fail immediately + const FILL_DEPTH: usize = 12; + + // load the FIFO + for _ in 0..core::cmp::min(FILL_DEPTH, len) { + self.load_fifo(*bytes.next().unwrap()); + } + + let status_reader = self.i2c_base.i2c.s0_status().read(); + let mut load_if_next_available = || { + if let Some(next_byte) = bytes.next() { + self.load_fifo(*next_byte); + } + }; + loop { + if status_reader.nackdata().bit_is_set() { + self.clear_tx_fifo(); + return Err(Error::NackData); + } else if status_reader.idle().bit_is_set() { + return Ok(()); + } else { + while !status_reader.txnfull().bit_is_set() { + load_if_next_available(); + } + } + } + } + + pub fn read(&mut self, buffer: &mut [u8]) -> Result<(), Error> { + let len = buffer.len(); + // It should theoretically possible to transfer larger data sizes by tracking + // the number of sent words and setting it to 0x7fe as soon as only that many + // bytes are remaining. However, large transfer like this are not common. This + // feature will therefore not be supported for now. + if len > 0x7fe { + return Err(Error::DataTooLarge); + } + // Clear the receive FIFO + self.clear_rx_fifo(); + + let mut buf_iter = buffer.iter_mut(); + let mut read_bytes = 0; + let mut read_if_next_available = || { + if let Some(next_byte) = buf_iter.next() { + *next_byte = self.read_fifo(); + } + }; + loop { + let status_reader = self.i2c_base.i2c.s0_status().read(); + if status_reader.idle().bit_is_set() { + if read_bytes != len { + return Err(Error::InsufficientDataReceived); + } + return Ok(()); + } else if status_reader.rxnempty().bit_is_set() { + read_bytes += 1; + read_if_next_available(); + } + } + } +} + +impl I2cSlave { + /// Create a new I2C slave for seven bit addresses + pub fn new( + i2c: I2c, + sys_cfg: &mut pac::Sysconfig, + cfg: SlaveConfig, + clocks: &Clocks, + speed_mode: I2cSpeed, + ) -> Result { + if let I2cAddress::TenBit(_) = cfg.addr { + return Err(InitError::WrongAddrMode); + } + Ok(Self::new_generic(i2c, sys_cfg, cfg, clocks, speed_mode)?) + } +} + +impl I2cSlave { + pub fn new_ten_bit_addr( + i2c: I2c, + sys_cfg: &mut pac::Sysconfig, + cfg: SlaveConfig, + clocks: &Clocks, + speed_mode: I2cSpeed, + ) -> Result { + Self::new_generic(i2c, sys_cfg, cfg, clocks, speed_mode) + } +} diff --git a/va416xx-hal/src/lib.rs b/va416xx-hal/src/lib.rs index 1b395cf..0c5ea66 100644 --- a/va416xx-hal/src/lib.rs +++ b/va416xx-hal/src/lib.rs @@ -9,8 +9,11 @@ pub mod prelude; pub mod clock; pub mod gpio; +pub mod i2c; +pub mod pwm; pub mod spi; pub mod time; +pub mod timer; pub mod typelevel; pub mod uart; pub mod wdt; @@ -23,22 +26,20 @@ pub enum FunSel { Sel3 = 0b11, } -/// Generic IRQ config which can be used to specify whether the HAL driver will -/// use the IRQSEL register to route an interrupt, and whether the IRQ will be unmasked in the -/// Cortex-M0 NVIC. Both are generally necessary for IRQs to work, but the user might perform -/// this steps themselves -#[derive(Debug, PartialEq, Eq, Clone, Copy)] -pub struct IrqCfg { - /// Interrupt target vector. Should always be set, might be required for disabling IRQs - pub irq: pac::Interrupt, - /// Specfiy whether IRQ should be routed to an IRQ vector using the IRQSEL peripheral - pub route: bool, - /// Specify whether the IRQ is unmasked in the Cortex-M NVIC - pub enable: bool, -} - -impl IrqCfg { - pub fn new(irq: pac::Interrupt, route: bool, enable: bool) -> Self { - IrqCfg { irq, route, enable } +/// Enable a specific interrupt using the NVIC peripheral. +/// +/// # Safety +/// +/// This function is `unsafe` because it can break mask-based critical sections. +#[inline] +pub unsafe fn enable_interrupt(irq: pac::Interrupt) { + unsafe { + cortex_m::peripheral::NVIC::unmask(irq); } } + +/// Disable a specific interrupt using the NVIC peripheral. +#[inline] +pub fn disable_interrupt(irq: pac::Interrupt) { + cortex_m::peripheral::NVIC::mask(irq); +} diff --git a/va416xx-hal/src/pwm.rs b/va416xx-hal/src/pwm.rs new file mode 100644 index 0000000..deb5db4 --- /dev/null +++ b/va416xx-hal/src/pwm.rs @@ -0,0 +1,388 @@ +//! API for Pulse-Width Modulation (PWM) +//! +//! The Vorago VA416xx devices use the TIM peripherals to perform PWM related tasks. +//! +//! ## Examples +//! +//! - [PWM example](https://egit.irs.uni-stuttgart.de/rust/va416xx-rs/src/branch/main/examples/simple/examples/pwm.rs) +use core::convert::Infallible; +use core::marker::PhantomData; + +use crate::pac; +use crate::{clock::Clocks, gpio::DynPinId}; +pub use crate::{gpio::PinId, time::Hertz, timer::*}; + +const DUTY_MAX: u16 = u16::MAX; + +pub struct PwmBase { + clock: Hertz, + /// For PWMB, this is the upper limit + current_duty: u16, + /// For PWMA, this value will not be used + current_lower_limit: u16, + current_period: Hertz, + current_rst_val: u32, +} + +enum StatusSelPwm { + PwmA = 3, + PwmB = 4, +} + +pub struct PwmA {} +pub struct PwmB {} + +//================================================================================================== +// Common +//================================================================================================== + +macro_rules! pwm_common_func { + () => { + #[inline] + fn enable_pwm_a(&mut self) { + self.reg + .reg() + .ctrl() + .modify(|_, w| unsafe { w.status_sel().bits(StatusSelPwm::PwmA as u8) }); + } + + #[inline] + fn enable_pwm_b(&mut self) { + self.reg + .reg() + .ctrl() + .modify(|_, w| unsafe { w.status_sel().bits(StatusSelPwm::PwmB as u8) }); + } + + #[inline] + pub fn get_period(&self) -> Hertz { + self.pwm_base.current_period + } + + #[inline] + pub fn set_period(&mut self, period: impl Into) { + self.pwm_base.current_period = period.into(); + // Avoid division by 0 + if self.pwm_base.current_period.raw() == 0 { + return; + } + self.pwm_base.current_rst_val = + self.pwm_base.clock.raw() / self.pwm_base.current_period.raw(); + self.reg + .reg() + .rst_value() + .write(|w| unsafe { w.bits(self.pwm_base.current_rst_val) }); + } + + #[inline] + pub fn disable(&mut self) { + self.reg.reg().ctrl().modify(|_, w| w.enable().clear_bit()); + } + + #[inline] + pub fn enable(&mut self) { + self.reg.reg().ctrl().modify(|_, w| w.enable().set_bit()); + } + + #[inline] + pub fn period(&self) -> Hertz { + self.pwm_base.current_period + } + + #[inline(always)] + pub fn duty(&self) -> u16 { + self.pwm_base.current_duty + } + }; +} + +macro_rules! pwmb_func { + () => { + pub fn pwmb_lower_limit(&self) -> u16 { + self.pwm_base.current_lower_limit + } + + pub fn pwmb_upper_limit(&self) -> u16 { + self.pwm_base.current_duty + } + + /// Set the lower limit for PWMB + /// + /// The PWM signal will be 1 as long as the current RST counter is larger than + /// the lower limit. For example, with a lower limit of 0.5 and and an upper limit + /// of 0.7, Only a fixed period between 0.5 * period and 0.7 * period will be in a high + /// state + pub fn set_pwmb_lower_limit(&mut self, duty: u16) { + self.pwm_base.current_lower_limit = duty; + let pwmb_val: u64 = (self.pwm_base.current_rst_val as u64 + * self.pwm_base.current_lower_limit as u64) + / DUTY_MAX as u64; + self.reg + .reg() + .pwmb_value() + .write(|w| unsafe { w.bits(pwmb_val as u32) }); + } + + /// Set the higher limit for PWMB + /// + /// The PWM signal will be 1 as long as the current RST counter is smaller than + /// the higher limit. For example, with a lower limit of 0.5 and and an upper limit + /// of 0.7, Only a fixed period between 0.5 * period and 0.7 * period will be in a high + /// state + pub fn set_pwmb_upper_limit(&mut self, duty: u16) { + self.pwm_base.current_duty = duty; + let pwma_val: u64 = (self.pwm_base.current_rst_val as u64 + * self.pwm_base.current_duty as u64) + / DUTY_MAX as u64; + self.reg + .reg() + .pwma_value() + .write(|w| unsafe { w.bits(pwma_val as u32) }); + } + }; +} + +//================================================================================================== +// Strongly typed PWM pin +//================================================================================================== + +pub struct PwmPin { + reg: TimAndPinRegister, + pwm_base: PwmBase, + mode: PhantomData, +} + +impl PwmPin +where + (Pin, Tim): ValidTimAndPin, +{ + /// Create a new stronlgy typed PWM pin + pub fn new( + pin_and_tim: (Pin, Tim), + sys_cfg: &mut pac::Sysconfig, + clocks: &Clocks, + initial_period: impl Into + Copy, + ) -> Self { + let mut pin = PwmPin { + pwm_base: PwmBase { + current_duty: 0, + current_lower_limit: 0, + current_period: initial_period.into(), + current_rst_val: 0, + clock: Tim::clock(clocks), + }, + reg: unsafe { TimAndPinRegister::new(pin_and_tim.0, pin_and_tim.1) }, + mode: PhantomData, + }; + sys_cfg + .tim_clk_enable() + .modify(|r, w| unsafe { w.bits(r.bits() | pin.reg.mask_32()) }); + pin.enable_pwm_a(); + pin.set_period(initial_period); + pin + } + + pub fn release(self) -> (Pin, Tim) { + self.reg.release() + } + + pwm_common_func!(); +} + +impl From> for PwmPin +where + (Pin, Tim): ValidTimAndPin, +{ + fn from(other: PwmPin) -> Self { + let mut pwmb = Self { + reg: other.reg, + pwm_base: other.pwm_base, + mode: PhantomData, + }; + pwmb.enable_pwm_b(); + pwmb + } +} + +impl From> for PwmPin +where + (PIN, TIM): ValidTimAndPin, +{ + fn from(other: PwmPin) -> Self { + let mut pwmb = Self { + reg: other.reg, + pwm_base: other.pwm_base, + mode: PhantomData, + }; + pwmb.enable_pwm_a(); + pwmb + } +} + +impl PwmPin +where + (Pin, Tim): ValidTimAndPin, +{ + pub fn pwma( + tim_and_pin: (Pin, Tim), + sys_cfg: &mut pac::Sysconfig, + clocks: &Clocks, + initial_period: impl Into + Copy, + ) -> Self { + let mut pin: PwmPin = + Self::new(tim_and_pin, sys_cfg, clocks, initial_period); + pin.enable_pwm_a(); + pin + } +} + +impl PwmPin +where + (Pin, Tim): ValidTimAndPin, +{ + pub fn pwmb( + tim_and_pin: (Pin, Tim), + sys_cfg: &mut pac::Sysconfig, + clocks: &Clocks, + initial_period: impl Into + Copy, + ) -> Self { + let mut pin: PwmPin = + Self::new(tim_and_pin, sys_cfg, clocks, initial_period); + pin.enable_pwm_b(); + pin + } +} + +//================================================================================================== +// Reduced PWM pin +//================================================================================================== + +/// Reduced version where type information is deleted +pub struct ReducedPwmPin { + reg: TimDynRegister, + pwm_base: PwmBase, + pin_id: DynPinId, + mode: PhantomData, +} + +impl From> for ReducedPwmPin { + fn from(pwm_pin: PwmPin) -> Self { + ReducedPwmPin { + reg: TimDynRegister::from(pwm_pin.reg), + pwm_base: pwm_pin.pwm_base, + pin_id: PIN::DYN, + mode: PhantomData, + } + } +} + +impl ReducedPwmPin { + pwm_common_func!(); +} + +impl From> for ReducedPwmPin { + fn from(other: ReducedPwmPin) -> Self { + let mut pwmb = Self { + reg: other.reg, + pwm_base: other.pwm_base, + pin_id: other.pin_id, + mode: PhantomData, + }; + pwmb.enable_pwm_b(); + pwmb + } +} + +impl From> for ReducedPwmPin { + fn from(other: ReducedPwmPin) -> Self { + let mut pwmb = Self { + reg: other.reg, + pwm_base: other.pwm_base, + pin_id: other.pin_id, + mode: PhantomData, + }; + pwmb.enable_pwm_a(); + pwmb + } +} + +//================================================================================================== +// PWMB implementations +//================================================================================================== + +impl PwmPin +where + (PIN, TIM): ValidTimAndPin, +{ + pwmb_func!(); +} + +impl ReducedPwmPin { + pwmb_func!(); +} + +//================================================================================================== +// Embedded HAL implementation: PWMA only +//================================================================================================== + +impl embedded_hal::pwm::ErrorType for PwmPin { + type Error = Infallible; +} + +impl embedded_hal::pwm::ErrorType for ReducedPwmPin { + type Error = Infallible; +} + +impl embedded_hal::pwm::SetDutyCycle for ReducedPwmPin { + #[inline] + fn max_duty_cycle(&self) -> u16 { + DUTY_MAX + } + + #[inline] + fn set_duty_cycle(&mut self, duty: u16) -> Result<(), Self::Error> { + self.pwm_base.current_duty = duty; + let pwma_val: u64 = (self.pwm_base.current_rst_val as u64 + * (DUTY_MAX as u64 - self.pwm_base.current_duty as u64)) + / DUTY_MAX as u64; + self.reg + .reg() + .pwma_value() + .write(|w| unsafe { w.bits(pwma_val as u32) }); + Ok(()) + } +} + +impl embedded_hal::pwm::SetDutyCycle for PwmPin { + #[inline] + fn max_duty_cycle(&self) -> u16 { + DUTY_MAX + } + + #[inline] + fn set_duty_cycle(&mut self, duty: u16) -> Result<(), Self::Error> { + self.pwm_base.current_duty = duty; + let pwma_val: u64 = (self.pwm_base.current_rst_val as u64 + * (DUTY_MAX as u64 - self.pwm_base.current_duty as u64)) + / DUTY_MAX as u64; + self.reg + .reg() + .pwma_value() + .write(|w| unsafe { w.bits(pwma_val as u32) }); + Ok(()) + } +} + +/// Get the corresponding u16 duty cycle from a percent value ranging between 0.0 and 1.0. +/// +/// Please note that this might load a lot of floating point code because this processor does not +/// have a FPU +pub fn get_duty_from_percent(percent: f32) -> u16 { + if percent > 1.0 { + DUTY_MAX + } else if percent <= 0.0 { + 0 + } else { + (percent * DUTY_MAX as f32) as u16 + } +} diff --git a/va416xx-hal/src/spi.rs b/va416xx-hal/src/spi.rs index 672e416..cc1acb3 100644 --- a/va416xx-hal/src/spi.rs +++ b/va416xx-hal/src/spi.rs @@ -1,3 +1,8 @@ +//! API for the SPI peripheral +//! +//! ## Examples +//! +//! - [Blocking SPI example](https://egit.irs.uni-stuttgart.de/rust/va416xx-rs/src/branch/main/examples/simple/examples/spi.rs) use core::{convert::Infallible, marker::PhantomData, ops::Deref}; use embedded_hal::spi::Mode; @@ -351,12 +356,14 @@ pub type SpiRegBlock = pac::spi0::RegisterBlock; /// format is the same for all SPI blocks. pub trait Instance: Deref { const IDX: u8; + const PERIPH_SEL: PeripheralSelect; fn ptr() -> *const SpiRegBlock; } impl Instance for pac::Spi0 { const IDX: u8 = 0; + const PERIPH_SEL: PeripheralSelect = PeripheralSelect::Spi0; fn ptr() -> *const SpiRegBlock { Self::ptr() @@ -365,6 +372,7 @@ impl Instance for pac::Spi0 { impl Instance for pac::Spi1 { const IDX: u8 = 1; + const PERIPH_SEL: PeripheralSelect = PeripheralSelect::Spi1; fn ptr() -> *const SpiRegBlock { Self::ptr() @@ -373,6 +381,7 @@ impl Instance for pac::Spi1 { impl Instance for pac::Spi2 { const IDX: u8 = 2; + const PERIPH_SEL: PeripheralSelect = PeripheralSelect::Spi2; fn ptr() -> *const SpiRegBlock { Self::ptr() @@ -562,6 +571,7 @@ where } } +/* macro_rules! spi_ctor { ($spiI:ident, $PeriphSel: path) => { /// Create a new SPI struct @@ -652,6 +662,7 @@ macro_rules! spi_ctor { } }; } +*/ impl< SpiI: Instance, @@ -663,10 +674,92 @@ impl< where >::Error: core::fmt::Debug, { - spi_ctor!(spi0, PeripheralSelect::Spi0); - spi_ctor!(spi1, PeripheralSelect::Spi1); - spi_ctor!(spi2, PeripheralSelect::Spi2); - spi_ctor!(spi3, PeripheralSelect::Spi3); + /// Create a new SPI struct + /// + /// You can delete the pin type information by calling the + /// [`downgrade`](Self::downgrade) function + /// + /// ## Arguments + /// * `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 + /// * `transfer_cfg` - Optional initial transfer configuration which includes + /// configuration which can change across individual SPI transfers like SPI mode + /// or SPI clock. If only one device is connected, this configuration only needs + /// to be done once. + /// * `syscfg` - Can be passed optionally to enable the peripheral clock + pub fn new( + spi: SpiI, + pins: (Sck, Miso, Mosi), + clocks: &crate::clock::Clocks, + spi_cfg: SpiConfig, + syscfg: &mut pac::Sysconfig, + transfer_cfg: Option<&ErasedTransferConfig>, + ) -> Self { + crate::clock::enable_peripheral_clock(syscfg, SpiI::PERIPH_SEL); + let SpiConfig { + ser_clock_rate_div, + ms, + slave_output_disable, + loopback_mode, + master_delayer_capture, + } = spi_cfg; + let mut mode = embedded_hal::spi::MODE_0; + let mut clk_prescale = 0x02; + let mut ss = 0; + let mut init_blockmode = false; + let apb1_clk = clocks.apb1(); + if let Some(transfer_cfg) = transfer_cfg { + mode = transfer_cfg.mode; + clk_prescale = + apb1_clk.raw() / (transfer_cfg.spi_clk.raw() * (ser_clock_rate_div as u32 + 1)); + if transfer_cfg.hw_cs != HwChipSelectId::Invalid { + ss = transfer_cfg.hw_cs as u8; + } + init_blockmode = transfer_cfg.blockmode; + } + + let (cpo_bit, cph_bit) = mode_to_cpo_cph_bit(mode); + spi.ctrl0().write(|w| { + unsafe { + w.size().bits(Word::word_reg()); + w.scrdv().bits(ser_clock_rate_div); + // Clear clock phase and polarity. Will be set to correct value for each + // transfer + w.spo().bit(cpo_bit); + w.sph().bit(cph_bit) + } + }); + spi.ctrl1().write(|w| { + w.lbm().bit(loopback_mode); + w.sod().bit(slave_output_disable); + w.ms().bit(ms); + w.mdlycap().bit(master_delayer_capture); + w.blockmode().bit(init_blockmode); + unsafe { w.ss().bits(ss) } + }); + + spi.fifo_clr().write(|w| { + w.rxfifo().set_bit(); + w.txfifo().set_bit() + }); + spi.clkprescale().write(|w| unsafe { w.bits(clk_prescale) }); + // Enable the peripheral as the last step as recommended in the + // programmers guide + spi.ctrl1().modify(|_, w| w.enable().set_bit()); + Spi { + inner: SpiBase { + spi, + cfg: spi_cfg, + apb1_clk, + fill_word: Default::default(), + blockmode: init_blockmode, + word: PhantomData, + }, + pins, + } + } #[inline] pub fn cfg_clock(&mut self, spi_clk: impl Into) { diff --git a/va416xx-hal/src/timer.rs b/va416xx-hal/src/timer.rs new file mode 100644 index 0000000..267317f --- /dev/null +++ b/va416xx-hal/src/timer.rs @@ -0,0 +1,802 @@ +//! API for the TIM peripherals +//! +//! ## Examples +//! +//! TODO. +use core::cell::Cell; + +use cortex_m::interrupt::Mutex; + +use crate::clock::Clocks; +use crate::gpio::{ + AltFunc1, AltFunc2, AltFunc3, DynPinId, Pin, PinId, PA0, PA1, PA10, PA11, PA12, PA13, PA14, + PA15, PA2, PA3, PA4, PA5, PA6, PA7, PB0, PB1, PB10, PB11, PB12, PB13, PB14, PB15, PB2, PB3, + PB4, PB5, PB6, PB7, PB8, PB9, PC0, PC1, PD0, PD1, PD10, PD11, PD12, PD13, PD14, PD15, PD2, PD3, + PD4, PD5, PD6, PD7, PD8, PD9, PE0, PE1, PE10, PE11, PE12, PE13, PE14, PE15, PE2, PE3, PE4, PE5, + PE6, PE7, PE8, PE9, PF0, PF1, PF10, PF11, PF12, PF13, PF14, PF15, PF2, PF3, PF4, PF5, PF6, PF7, + PF8, PF9, PG0, PG1, PG2, PG3, PG6, +}; +use crate::time::Hertz; +use crate::typelevel::Sealed; +use crate::{disable_interrupt, prelude::*}; +use crate::{enable_interrupt, pac}; + +pub static MS_COUNTER: Mutex> = Mutex::new(Cell::new(0)); + +//================================================================================================== +// Defintions +//================================================================================================== + +/// Interrupt events +//pub enum Event { +/// Timer timed out / count down ended +//TimeOut, +//} + +#[derive(Default, Debug, PartialEq, Eq, Copy, Clone)] +pub struct CascadeCtrl { + /// Enable Cascade 0 signal active as a requirement for counting + pub enb_start_src_csd0: bool, + /// Invert Cascade 0, making it active low + pub inv_csd0: bool, + /// Enable Cascade 1 signal active as a requirement for counting + pub enb_start_src_csd1: bool, + /// Invert Cascade 1, making it active low + pub inv_csd1: bool, + /// Specify required operation if both Cascade 0 and Cascade 1 are active. + /// 0 is a logical AND of both cascade signals, 1 is a logical OR + pub dual_csd_op: bool, + /// Enable trigger mode for Cascade 0. In trigger mode, couting will start with the selected + /// cascade signal active, but once the counter is active, cascade control will be ignored + pub trg_csd0: bool, + /// Trigger mode, identical to [`trg_csd0`](CascadeCtrl) but for Cascade 1 + pub trg_csd1: bool, + /// Enable Cascade 2 signal active as a requirement to stop counting. This mode is similar + /// to the REQ_STOP control bit, but signalled by a Cascade source + pub enb_stop_src_csd2: bool, + /// Invert Cascade 2, making it active low + pub inv_csd2: bool, + /// The counter is automatically disabled if the corresponding Cascade 2 level-sensitive input + /// souce is active when the count reaches 0. If the counter is not 0, the cascade control is + /// ignored + pub trg_csd2: bool, +} + +#[derive(Debug, PartialEq, Eq)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +pub enum CascadeSel { + Sel0 = 0, + Sel1 = 1, + Sel2 = 2, +} + +#[derive(Debug, PartialEq, Eq)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +pub struct InvalidCascadeSourceId; + +#[derive(Debug, PartialEq, Eq)] +#[cfg_attr(feature = "defmt", derive(defmt::Format))] +pub enum CascadeSource { + PortA(u8), + PortB(u8), + PortC(u8), + PortD(u8), + PortE(u8), + Tim(u8), + TxEv, + AdcIrq, + RomSbe, + RomMbe, + Ram0Sbe, + Ram0Mbe, + Ram1Sbe, + Ram2Mbe, + WdogIrq, +} + +impl CascadeSource { + fn id(&self) -> Result { + let port_check = |base: u8, id: u8| { + if id > 15 { + return Err(InvalidCascadeSourceId); + } + Ok(base + id) + }; + match self { + CascadeSource::PortA(id) => port_check(0, *id), + CascadeSource::PortB(id) => port_check(16, *id), + CascadeSource::PortC(id) => port_check(32, *id), + CascadeSource::PortD(id) => port_check(48, *id), + CascadeSource::PortE(id) => port_check(65, *id), + CascadeSource::Tim(id) => { + if *id > 23 { + return Err(InvalidCascadeSourceId); + } + Ok(80 + id) + } + CascadeSource::TxEv => Ok(104), + CascadeSource::AdcIrq => Ok(105), + CascadeSource::RomSbe => Ok(106), + CascadeSource::RomMbe => Ok(106), + CascadeSource::Ram0Sbe => Ok(108), + CascadeSource::Ram0Mbe => Ok(109), + CascadeSource::Ram1Sbe => Ok(110), + CascadeSource::Ram2Mbe => Ok(111), + CascadeSource::WdogIrq => Ok(112), + } + } +} + +//================================================================================================== +// Valid TIM and PIN combinations +//================================================================================================== + +pub trait TimPin { + const DYN: DynPinId; +} + +pub trait ValidTim { + // TIM ID ranging from 0 to 23 for 24 TIM peripherals + const TIM_ID: u8; + const IRQ: pac::Interrupt; + + fn clock(clocks: &Clocks) -> Hertz { + if Self::TIM_ID <= 15 { + clocks.apb1() + } else { + clocks.apb2() + } + } +} + +macro_rules! tim_markers { + ( + $( + ($TimX:path, $id:expr, $Irq:path), + )+ + ) => { + $( + impl ValidTim for $TimX { + const TIM_ID: u8 = $id; + const IRQ: pac::Interrupt = $Irq; + } + )+ + }; +} + +tim_markers!( + (pac::Tim0, 0, pac::Interrupt::TIM0), + (pac::Tim1, 1, pac::Interrupt::TIM1), + (pac::Tim2, 2, pac::Interrupt::TIM2), + (pac::Tim3, 3, pac::Interrupt::TIM3), + (pac::Tim4, 4, pac::Interrupt::TIM4), + (pac::Tim5, 5, pac::Interrupt::TIM5), + (pac::Tim6, 6, pac::Interrupt::TIM6), + (pac::Tim7, 7, pac::Interrupt::TIM7), + (pac::Tim8, 8, pac::Interrupt::TIM8), + (pac::Tim9, 9, pac::Interrupt::TIM9), + (pac::Tim10, 10, pac::Interrupt::TIM10), + (pac::Tim11, 11, pac::Interrupt::TIM11), + (pac::Tim12, 12, pac::Interrupt::TIM12), + (pac::Tim13, 13, pac::Interrupt::TIM13), + (pac::Tim14, 14, pac::Interrupt::TIM14), + (pac::Tim15, 15, pac::Interrupt::TIM15), + (pac::Tim16, 16, pac::Interrupt::TIM16), + (pac::Tim17, 17, pac::Interrupt::TIM17), + (pac::Tim18, 18, pac::Interrupt::TIM18), + (pac::Tim19, 19, pac::Interrupt::TIM19), + (pac::Tim20, 20, pac::Interrupt::TIM20), + (pac::Tim21, 21, pac::Interrupt::TIM21), + (pac::Tim22, 22, pac::Interrupt::TIM22), + (pac::Tim23, 23, pac::Interrupt::TIM23), +); + +pub trait ValidTimAndPin: Sealed {} + +macro_rules! valid_pin_and_tims { + ( + $( + ($PinX:ident, $AltFunc:ident, $TimX:path), + )+ + ) => { + $( + impl TimPin for Pin<$PinX, $AltFunc> + where + $PinX: PinId, + { + const DYN: DynPinId = $PinX::DYN; + } + + impl< + PinInstance: TimPin, + Tim: ValidTim + > ValidTimAndPin for (Pin<$PinX, $AltFunc>, $TimX) + where + Pin<$PinX, $AltFunc>: TimPin, + $PinX: PinId, + { + } + + impl Sealed for (Pin<$PinX, $AltFunc>, $TimX) {} + )+ + }; +} + +valid_pin_and_tims!( + (PA0, AltFunc1, pac::Tim0), + (PA1, AltFunc1, pac::Tim1), + (PA2, AltFunc1, pac::Tim2), + (PA3, AltFunc1, pac::Tim3), + (PA4, AltFunc1, pac::Tim4), + (PA5, AltFunc1, pac::Tim5), + (PA6, AltFunc1, pac::Tim6), + (PA7, AltFunc1, pac::Tim7), + (PA10, AltFunc2, pac::Tim23), + (PA11, AltFunc2, pac::Tim22), + (PA12, AltFunc2, pac::Tim21), + (PA13, AltFunc2, pac::Tim20), + (PA14, AltFunc2, pac::Tim19), + (PA15, AltFunc2, pac::Tim18), + (PB0, AltFunc2, pac::Tim17), + (PB1, AltFunc2, pac::Tim16), + (PB2, AltFunc2, pac::Tim15), + (PB3, AltFunc2, pac::Tim14), + (PB4, AltFunc2, pac::Tim13), + (PB5, AltFunc2, pac::Tim12), + (PB6, AltFunc2, pac::Tim11), + (PB7, AltFunc2, pac::Tim10), + (PB8, AltFunc2, pac::Tim9), + (PB9, AltFunc2, pac::Tim8), + (PB10, AltFunc2, pac::Tim7), + (PB11, AltFunc2, pac::Tim6), + (PB12, AltFunc2, pac::Tim5), + (PB13, AltFunc2, pac::Tim4), + (PB14, AltFunc2, pac::Tim3), + (PB15, AltFunc2, pac::Tim2), + (PC0, AltFunc2, pac::Tim1), + (PC1, AltFunc2, pac::Tim0), + (PD0, AltFunc2, pac::Tim0), + (PD1, AltFunc2, pac::Tim1), + (PD2, AltFunc2, pac::Tim2), + (PD3, AltFunc2, pac::Tim3), + (PD4, AltFunc2, pac::Tim4), + (PD5, AltFunc2, pac::Tim5), + (PD6, AltFunc2, pac::Tim6), + (PD7, AltFunc2, pac::Tim7), + (PD8, AltFunc2, pac::Tim8), + (PD9, AltFunc2, pac::Tim9), + (PD10, AltFunc2, pac::Tim10), + (PD11, AltFunc2, pac::Tim11), + (PD12, AltFunc2, pac::Tim12), + (PD13, AltFunc2, pac::Tim13), + (PD14, AltFunc2, pac::Tim14), + (PD15, AltFunc2, pac::Tim15), + (PE0, AltFunc2, pac::Tim16), + (PE1, AltFunc2, pac::Tim17), + (PE2, AltFunc2, pac::Tim18), + (PE3, AltFunc2, pac::Tim19), + (PE4, AltFunc2, pac::Tim20), + (PE5, AltFunc2, pac::Tim21), + (PE6, AltFunc2, pac::Tim22), + (PE7, AltFunc2, pac::Tim23), + (PE8, AltFunc3, pac::Tim16), + (PE9, AltFunc3, pac::Tim17), + (PE10, AltFunc3, pac::Tim18), + (PE11, AltFunc3, pac::Tim19), + (PE12, AltFunc3, pac::Tim20), + (PE13, AltFunc3, pac::Tim21), + (PE14, AltFunc3, pac::Tim22), + (PE15, AltFunc3, pac::Tim23), + (PF0, AltFunc3, pac::Tim0), + (PF1, AltFunc3, pac::Tim1), + (PF2, AltFunc3, pac::Tim2), + (PF3, AltFunc3, pac::Tim3), + (PF4, AltFunc3, pac::Tim4), + (PF5, AltFunc3, pac::Tim5), + (PF6, AltFunc3, pac::Tim6), + (PF7, AltFunc3, pac::Tim7), + (PF8, AltFunc3, pac::Tim8), + (PF9, AltFunc3, pac::Tim9), + (PF10, AltFunc3, pac::Tim10), + (PF11, AltFunc3, pac::Tim11), + (PF12, AltFunc3, pac::Tim12), + (PF13, AltFunc2, pac::Tim19), + (PF14, AltFunc2, pac::Tim20), + (PF15, AltFunc2, pac::Tim21), + (PG0, AltFunc2, pac::Tim22), + (PG1, AltFunc2, pac::Tim23), + (PG2, AltFunc1, pac::Tim9), + (PG3, AltFunc1, pac::Tim10), + (PG6, AltFunc1, pac::Tim12), +); + +//================================================================================================== +// Register Interface for TIM registers and TIM pins +//================================================================================================== + +/// Clear the reset bit of the TIM, holding it in reset +/// +/// # Safety +/// +/// Only the bit related to the corresponding TIM peripheral is modified +#[inline] +fn assert_tim_reset(syscfg: &mut pac::Sysconfig, tim_id: u8) { + syscfg + .tim_reset() + .modify(|r, w| unsafe { w.bits(r.bits() & !(1 << tim_id as u32)) }) +} + +#[inline] +fn deassert_tim_reset(syscfg: &mut pac::Sysconfig, tim_id: u8) { + syscfg + .tim_reset() + .modify(|r, w| unsafe { w.bits(r.bits() | (1 << tim_id as u32)) }) +} + +pub type TimRegBlock = pac::tim0::RegisterBlock; + +/// Register interface. +/// +/// This interface provides valid TIM pins a way to access their corresponding TIM +/// registers +/// +/// # Safety +/// +/// Users should only implement the [`tim_id`] function. No default function +/// implementations should be overridden. The implementing type must also have +/// "control" over the corresponding pin ID, i.e. it must guarantee that a each +/// pin ID is a singleton. +pub(super) unsafe trait TimRegInterface { + fn tim_id(&self) -> u8; + + const PORT_BASE: *const pac::tim0::RegisterBlock = pac::Tim0::ptr() as *const _; + + /// All 24 TIM blocks are identical. This helper functions returns the correct + /// memory mapped peripheral depending on the TIM ID. + #[inline(always)] + fn reg(&self) -> &TimRegBlock { + unsafe { &*Self::PORT_BASE.offset(self.tim_id() as isize) } + } + + #[inline(always)] + fn mask_32(&self) -> u32 { + 1 << self.tim_id() + } + + /// Clear the reset bit of the TIM, holding it in reset + /// + /// # Safety + /// + /// Only the bit related to the corresponding TIM peripheral is modified + #[inline] + #[allow(dead_code)] + fn assert_tim_reset(&self, syscfg: &mut pac::Sysconfig) { + assert_tim_reset(syscfg, self.tim_id()); + } + + #[inline] + #[allow(dead_code)] + fn deassert_time_reset(&self, syscfg: &mut pac::Sysconfig) { + deassert_tim_reset(syscfg, self.tim_id()); + } +} + +/// Provide a safe register interface for [`ValidTimAndPin`]s +/// +/// This `struct` takes ownership of a [`ValidTimAndPin`] and provides an API to +/// access the corresponding registers. +pub(super) struct TimAndPinRegister { + pin: Pin, + tim: Tim, +} + +pub(super) struct TimRegister { + tim: TIM, +} + +impl TimRegister { + #[inline] + pub(super) unsafe fn new(tim: TIM) -> Self { + TimRegister { tim } + } + + pub(super) fn release(self) -> TIM { + self.tim + } +} + +unsafe impl TimRegInterface for TimRegister { + #[inline(always)] + fn tim_id(&self) -> u8 { + Tim::TIM_ID + } +} + +impl TimAndPinRegister +where + (Pin, Tim): ValidTimAndPin, +{ + #[inline] + pub(super) unsafe fn new(pin: Pin, tim: Tim) -> Self { + TimAndPinRegister { pin, tim } + } + + pub(super) fn release(self) -> (Pin, Tim) { + (self.pin, self.tim) + } +} + +unsafe impl TimRegInterface for TimAndPinRegister { + #[inline(always)] + fn tim_id(&self) -> u8 { + Tim::TIM_ID + } +} + +pub(super) struct TimDynRegister { + tim_id: u8, + #[allow(dead_code)] + pin_id: DynPinId, +} + +impl From> for TimDynRegister { + fn from(_reg: TimAndPinRegister) -> Self { + Self { + tim_id: Tim::TIM_ID, + pin_id: Pin::DYN, + } + } +} + +unsafe impl TimRegInterface for TimDynRegister { + #[inline(always)] + fn tim_id(&self) -> u8 { + self.tim_id + } +} + +//================================================================================================== +// Timers +//================================================================================================== + +/// Hardware timers +pub struct CountdownTimer { + tim: TimRegister, + curr_freq: Hertz, + clock: Hertz, + rst_val: u32, + last_cnt: u32, + listening: bool, +} + +#[inline] +fn enable_tim_clk(syscfg: &mut pac::Sysconfig, idx: u8) { + syscfg + .tim_clk_enable() + .modify(|r, w| unsafe { w.bits(r.bits() | (1 << idx)) }); +} + +unsafe impl TimRegInterface for CountdownTimer { + #[inline] + fn tim_id(&self) -> u8 { + TIM::TIM_ID + } +} + +impl CountdownTimer { + /// Create a new countdown timer, but does not start it. + /// + /// You can use [Self::start] to start the countdown timer, and you may optionally call + /// [Self::listen] to enable interrupts for the TIM peripheral as well. + pub fn new(syscfg: &mut pac::Sysconfig, tim: Tim, clocks: &Clocks) -> Self { + enable_tim_clk(syscfg, Tim::TIM_ID); + assert_tim_reset(syscfg, Tim::TIM_ID); + cortex_m::asm::nop(); + cortex_m::asm::nop(); + deassert_tim_reset(syscfg, Tim::TIM_ID); + + CountdownTimer { + tim: unsafe { TimRegister::new(tim) }, + clock: Tim::clock(clocks), + rst_val: 0, + curr_freq: 0_u32.Hz(), + listening: false, + last_cnt: 0, + } + } + + #[inline] + pub fn start(&mut self, timeout: impl Into) { + self.load(timeout); + self.enable(); + } + + /// Listen for events. Depending on the IRQ configuration, this also activates the IRQ in the + /// IRQSEL peripheral for the provided interrupt and unmasks the interrupt + pub fn listen(&mut self) { + self.listening = true; + self.enable_interrupt(); + unsafe { enable_interrupt(Tim::IRQ) } + } + + /// Return `Ok` if the timer has wrapped. Peripheral will automatically clear the + /// flag and restart the time if configured correctly + pub fn wait(&mut self) -> nb::Result<(), void::Void> { + let cnt = self.tim.reg().cnt_value().read().bits(); + if (cnt > self.last_cnt) || cnt == 0 { + self.last_cnt = self.rst_val; + Ok(()) + } else { + self.last_cnt = cnt; + Err(nb::Error::WouldBlock) + } + } + + pub fn stop(&mut self) { + self.tim.reg().ctrl().write(|w| w.enable().clear_bit()); + } + + pub fn unlisten(&mut self) { + self.listening = true; + self.disable_interrupt(); + disable_interrupt(Tim::IRQ); + } + + #[inline(always)] + pub fn enable_interrupt(&mut self) { + self.tim.reg().ctrl().modify(|_, w| w.irq_enb().set_bit()); + } + + #[inline(always)] + pub fn disable_interrupt(&mut self) { + self.tim.reg().ctrl().modify(|_, w| w.irq_enb().clear_bit()); + } + + pub fn release(self, syscfg: &mut pac::Sysconfig) -> Tim { + self.tim.reg().ctrl().write(|w| w.enable().clear_bit()); + syscfg + .tim_clk_enable() + .modify(|r, w| unsafe { w.bits(r.bits() & !(1 << Tim::TIM_ID)) }); + self.tim.release() + } + + /// Load the count down timer with a timeout but do not start it. + pub fn load(&mut self, timeout: impl Into) { + self.tim.reg().ctrl().modify(|_, w| w.enable().clear_bit()); + self.curr_freq = timeout.into(); + self.rst_val = self.clock.raw() / self.curr_freq.raw(); + self.set_reload(self.rst_val); + self.set_count(0); + } + + #[inline(always)] + pub fn set_reload(&mut self, val: u32) { + self.tim.reg().rst_value().write(|w| unsafe { w.bits(val) }); + } + + #[inline(always)] + pub fn set_count(&mut self, val: u32) { + self.tim.reg().cnt_value().write(|w| unsafe { w.bits(val) }); + } + + #[inline(always)] + pub fn count(&self) -> u32 { + self.tim.reg().cnt_value().read().bits() + } + + #[inline(always)] + pub fn enable(&mut self) { + self.tim.reg().ctrl().modify(|_, w| w.enable().set_bit()); + } + + #[inline(always)] + pub fn disable(&mut self) { + self.tim.reg().ctrl().modify(|_, w| w.enable().clear_bit()); + } + + /// Disable the counter, setting both enable and active bit to 0 + #[inline] + pub fn auto_disable(self, enable: bool) -> Self { + if enable { + self.tim + .reg() + .ctrl() + .modify(|_, w| w.auto_disable().set_bit()); + } else { + self.tim + .reg() + .ctrl() + .modify(|_, w| w.auto_disable().clear_bit()); + } + self + } + + /// This option only applies when the Auto-Disable functionality is 0. + /// + /// The active bit is changed to 0 when count reaches 0, but the counter stays + /// enabled. When Auto-Disable is 1, Auto-Deactivate is implied + #[inline] + pub fn auto_deactivate(self, enable: bool) -> Self { + if enable { + self.tim + .reg() + .ctrl() + .modify(|_, w| w.auto_deactivate().set_bit()); + } else { + self.tim + .reg() + .ctrl() + .modify(|_, w| w.auto_deactivate().clear_bit()); + } + self + } + + /// Configure the cascade parameters + #[inline] + pub fn cascade_control(&mut self, ctrl: CascadeCtrl) { + self.tim.reg().csd_ctrl().write(|w| { + w.csden0().bit(ctrl.enb_start_src_csd0); + w.csdinv0().bit(ctrl.inv_csd0); + w.csden1().bit(ctrl.enb_start_src_csd1); + w.csdinv1().bit(ctrl.inv_csd1); + w.dcasop().bit(ctrl.dual_csd_op); + w.csdtrg0().bit(ctrl.trg_csd0); + w.csdtrg1().bit(ctrl.trg_csd1); + w.csden2().bit(ctrl.enb_stop_src_csd2); + w.csdinv2().bit(ctrl.inv_csd2); + w.csdtrg2().bit(ctrl.trg_csd2) + }); + } + + #[inline] + pub fn cascade_0_source(&mut self, src: CascadeSource) -> Result<(), InvalidCascadeSourceId> { + let id = src.id()?; + self.tim + .reg() + .cascade0() + .write(|w| unsafe { w.cassel().bits(id) }); + Ok(()) + } + + #[inline] + pub fn cascade_1_source(&mut self, src: CascadeSource) -> Result<(), InvalidCascadeSourceId> { + let id = src.id()?; + self.tim + .reg() + .cascade1() + .write(|w| unsafe { w.cassel().bits(id) }); + Ok(()) + } + + #[inline] + pub fn cascade_2_source(&mut self, src: CascadeSource) -> Result<(), InvalidCascadeSourceId> { + let id = src.id()?; + self.tim + .reg() + .cascade2() + .write(|w| unsafe { w.cassel().bits(id) }); + Ok(()) + } + + #[inline] + pub fn curr_freq(&self) -> Hertz { + self.curr_freq + } + + #[inline] + pub fn listening(&self) -> bool { + self.listening + } +} + +impl embedded_hal::delay::DelayNs for CountdownTimer { + fn delay_ns(&mut self, ns: u32) { + let ticks = (u64::from(ns)) * (u64::from(self.clock.raw())) / 1_000_000_000; + + let full_cycles = ticks >> 32; + let mut last_count; + let mut new_count; + if full_cycles > 0 { + self.set_reload(u32::MAX); + self.set_count(u32::MAX); + self.enable(); + + for _ in 0..full_cycles { + // Always ensure that both values are the same at the start. + new_count = self.count(); + last_count = new_count; + loop { + new_count = self.count(); + if new_count == 0 { + // Wait till timer has wrapped. + while self.count() == 0 { + cortex_m::asm::nop() + } + break; + } + // Timer has definitely wrapped. + if new_count > last_count { + break; + } + last_count = new_count; + } + } + } + let ticks = (ticks & u32::MAX as u64) as u32; + self.disable(); + if ticks > 1 { + self.set_reload(ticks); + self.set_count(ticks); + self.enable(); + last_count = ticks; + + loop { + new_count = self.count(); + if new_count == 0 || (new_count > last_count) { + break; + } + last_count = new_count; + } + } + + self.disable(); + } +} + +//================================================================================================== +// MS tick implementations +//================================================================================================== + +// Set up a millisecond timer on TIM0. Please note that the user still has to provide an IRQ handler +// which should call [default_ms_irq_handler]. +pub fn set_up_ms_tick( + sys_cfg: &mut pac::Sysconfig, + tim: Tim, + clocks: &Clocks, +) -> CountdownTimer { + let mut ms_timer = CountdownTimer::new(sys_cfg, tim, clocks); + ms_timer.listen(); + ms_timer.start(1000.Hz()); + ms_timer +} + +/// This function can be called in a specified interrupt handler to increment +/// the MS counter +pub fn default_ms_irq_handler() { + cortex_m::interrupt::free(|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 { + cortex_m::interrupt::free(|cs| MS_COUNTER.borrow(cs).get()) +} + +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(); + } + } +} diff --git a/va416xx-hal/src/uart.rs b/va416xx-hal/src/uart.rs index b798e23..7bd26e4 100644 --- a/va416xx-hal/src/uart.rs +++ b/va416xx-hal/src/uart.rs @@ -1,15 +1,21 @@ +//! # API for the UART peripheral +//! +//! ## Examples +//! +//! - [UART simple example](https://egit.irs.uni-stuttgart.de/rust/va416xx-rs/src/branch/main/examples/simple/examples/uart.rs) use core::marker::PhantomData; use core::ops::Deref; use embedded_hal_nb::serial::Read; use fugit::RateExtU32; -use crate::clock::{self, Clocks}; +use crate::clock::{Clocks, PeripheralSelect}; use crate::gpio::{AltFunc1, Pin, PD11, PD12, PE2, PE3, PF11, PF12, PF8, PF9, PG0, PG1}; use crate::time::Hertz; +use crate::{disable_interrupt, enable_interrupt}; use crate::{ gpio::{AltFunc2, AltFunc3, PA2, PA3, PB14, PB15, PC14, PC15, PC4, PC5}, - pac::{uart0 as uart_base, Uart0, Uart1, Uart2}, + pac::{self, uart0 as uart_base, Uart0, Uart1, Uart2}, }; //================================================================================================== @@ -332,10 +338,46 @@ impl Tx { pub trait Instance: Deref { const IDX: u8; + const PERIPH_SEL: PeripheralSelect; + const IRQ_RX: pac::Interrupt; + const IRQ_TX: pac::Interrupt; fn ptr() -> *const uart_base::RegisterBlock; } +impl Instance for Uart0 { + const IDX: u8 = 0; + const PERIPH_SEL: PeripheralSelect = PeripheralSelect::Uart0; + const IRQ_RX: pac::Interrupt = pac::Interrupt::UART0_RX; + const IRQ_TX: pac::Interrupt = pac::Interrupt::UART0_TX; + + fn ptr() -> *const uart_base::RegisterBlock { + Uart0::ptr() as *const _ + } +} + +impl Instance for Uart1 { + const IDX: u8 = 1; + const PERIPH_SEL: PeripheralSelect = PeripheralSelect::Uart1; + const IRQ_RX: pac::Interrupt = pac::Interrupt::UART1_RX; + const IRQ_TX: pac::Interrupt = pac::Interrupt::UART1_TX; + + fn ptr() -> *const uart_base::RegisterBlock { + Uart1::ptr() as *const _ + } +} + +impl Instance for Uart2 { + const IDX: u8 = 2; + const PERIPH_SEL: PeripheralSelect = PeripheralSelect::Uart2; + const IRQ_RX: pac::Interrupt = pac::Interrupt::UART2_RX; + const IRQ_TX: pac::Interrupt = pac::Interrupt::UART2_TX; + + fn ptr() -> *const uart_base::RegisterBlock { + Uart2::ptr() as *const _ + } +} + impl UartBase { fn init(self, config: Config, clocks: &Clocks) -> Self { if Uart::IDX == 2 { @@ -460,6 +502,7 @@ impl UartBase { w.rxenable().clear_bit(); w.txenable().clear_bit() }); + disable_interrupt(Uart::IRQ_RX); self.uart } @@ -468,10 +511,45 @@ impl UartBase { } } -impl Uart -where - UartInstance: Instance, -{ +impl Uart { + pub fn new( + uart: UartInstance, + pins: Pins, + config: impl Into, + syscfg: &mut va416xx::Sysconfig, + clocks: &Clocks, + ) -> Self { + crate::clock::enable_peripheral_clock(syscfg, UartInstance::PERIPH_SEL); + Uart { + inner: UartBase { + uart, + tx: Tx::new(), + rx: Rx::new(), + }, + pins, + } + .init(config.into(), clocks) + } + + pub fn new_with_clock_freq( + uart: UartInstance, + pins: Pins, + config: impl Into, + syscfg: &mut va416xx::Sysconfig, + clock: impl Into, + ) -> Self { + crate::clock::enable_peripheral_clock(syscfg, UartInstance::PERIPH_SEL); + Uart { + inner: UartBase { + uart, + tx: Tx::new(), + rx: Rx::new(), + }, + pins, + } + .init_with_clock_freq(config.into(), clock.into()) + } + fn init(mut self, config: Config, clocks: &Clocks) -> Self { self.inner = self.inner.init(config, clocks); self @@ -584,6 +662,7 @@ impl UartWithIrqBase { self.inner.enable_rx(); self.inner.enable_tx(); self.enable_rx_irq_sources(enb_timeout_irq); + unsafe { enable_interrupt(Uart::IRQ_RX) }; Ok(()) } @@ -783,87 +862,6 @@ impl UartWithIrq { } } -impl Instance for Uart0 { - const IDX: u8 = 0; - - fn ptr() -> *const uart_base::RegisterBlock { - Uart0::ptr() as *const _ - } -} - -impl Instance for Uart1 { - const IDX: u8 = 1; - - fn ptr() -> *const uart_base::RegisterBlock { - Uart1::ptr() as *const _ - } -} - -impl Instance for Uart2 { - const IDX: u8 = 2; - - fn ptr() -> *const uart_base::RegisterBlock { - Uart2::ptr() as *const _ - } -} - -macro_rules! uart_impl { - ($($Uartx:ident: ($uartx:ident, $clk_enb_enum:path),)+) => { - $( - - impl> Uart<$Uartx, Pins> { - pub fn $uartx( - uart: $Uartx, - pins: Pins, - config: impl Into, - syscfg: &mut va416xx::Sysconfig, - clocks: &Clocks - ) -> Self - { - crate::clock::enable_peripheral_clock(syscfg, $clk_enb_enum); - Uart { - inner: UartBase { - uart, - tx: Tx::new(), - rx: Rx::new(), - }, - pins, - }.init(config.into(), clocks) - } - - paste::paste! { - pub fn [ <$uartx _with_clock_freq> ]( - uart: $Uartx, - pins: Pins, - config: impl Into, - syscfg: &mut va416xx::Sysconfig, - clock: impl Into, - ) -> Self - { - crate::clock::enable_peripheral_clock(syscfg, $clk_enb_enum); - Uart { - inner: UartBase { - uart, - tx: Tx::new(), - rx: Rx::new(), - }, - pins, - }.init_with_clock_freq(config.into(), clock.into()) - } - - } - } - - )+ - } -} - -uart_impl! { - Uart0: (uart0, clock::PeripheralClocks::Uart0), - Uart1: (uart1, clock::PeripheralClocks::Uart1), - Uart2: (uart2, clock::PeripheralClocks::Uart2), -} - impl embedded_io::Error for Error { fn kind(&self) -> embedded_io::ErrorKind { embedded_io::ErrorKind::Other diff --git a/va416xx-hal/src/wdt.rs b/va416xx-hal/src/wdt.rs index 320c029..c5594b3 100644 --- a/va416xx-hal/src/wdt.rs +++ b/va416xx-hal/src/wdt.rs @@ -1,9 +1,15 @@ +//! # API for the Watchdog peripheral +//! +//! ## Examples +//! +//! - [Watchdog simple example](https://egit.irs.uni-stuttgart.de/rust/va416xx-rs/src/branch/main/examples/simple/examples/wdt.rs) use crate::time::Hertz; use crate::{ clock::{Clocks, PeripheralSelect}, pac, prelude::SyscfgExt, }; +use crate::{disable_interrupt, enable_interrupt}; pub const WDT_UNLOCK_VALUE: u32 = 0x1ACC_E551; @@ -19,14 +25,12 @@ pub struct WdtController { /// This function is `unsafe` because it can break mask-based critical sections. #[inline] pub unsafe fn enable_wdt_interrupts() { - unsafe { - cortex_m::peripheral::NVIC::unmask(pac::Interrupt::WATCHDOG); - } + enable_interrupt(pac::Interrupt::WATCHDOG) } #[inline] pub fn disable_wdt_interrupts() { - cortex_m::peripheral::NVIC::mask(pac::Interrupt::WATCHDOG); + disable_interrupt(pac::Interrupt::WATCHDOG) } impl WdtController { diff --git a/vorago-peb1/Cargo.toml b/vorago-peb1/Cargo.toml index 4932f59..bae4c16 100644 --- a/vorago-peb1/Cargo.toml +++ b/vorago-peb1/Cargo.toml @@ -19,11 +19,12 @@ embedded-hal = "1" path = "../va416xx-hal" version = "0.1.0" +[dependencies.lis2dh12] +git = "https://github.com/us-irs/lis2dh12.git" +# path = "../../lis2dh12" +branch = "all-features" +version = "0.7" +features = ["out_f32"] + [features] rt = ["va416xx-hal/rt"] - -[dev-dependencies] -panic-rtt-target = { version = "0.1.3" } -rtt-target = { version = "0.5" } -panic-halt = "0.2" -cortex-m = { version = "0.7.6", features = ["critical-section-single-core"]} diff --git a/vorago-peb1/src/lib.rs b/vorago-peb1/src/lib.rs index 0c9ac1a..5cb944e 100644 --- a/vorago-peb1/src/lib.rs +++ b/vorago-peb1/src/lib.rs @@ -1 +1,50 @@ +//! Board support crate for the VORAGO PEB1 board. #![no_std] + +pub use lis2dh12; + +/// Support for the LIS2DH12 accelerometer on the GPIO board. +pub mod accelerometer { + + use lis2dh12::{self, detect_i2c_addr, AddrDetectionError, Lis2dh12}; + use va416xx_hal::{ + clock::Clocks, + i2c::{self, ClockTooSlowForFastI2c, I2cMaster, I2cSpeed, MasterConfig}, + pac, + }; + + // Accelerometer located on the GPIO board. + pub type Accelerometer = Lis2dh12>; + + #[derive(Debug)] + pub enum ConstructorError { + ClkError(ClockTooSlowForFastI2c), + AddrDetectionError(AddrDetectionError), + AccelerometerError(lis2dh12::Error), + } + + pub fn new_with_addr_detection( + i2c: pac::I2c0, + sysconfig: &mut pac::Sysconfig, + clocks: &Clocks, + ) -> Result { + let mut i2c_master = I2cMaster::new( + i2c, + sysconfig, + MasterConfig::default(), + clocks, + I2cSpeed::Regular100khz, + ) + .map_err(ConstructorError::ClkError)?; + let slave_addr = + detect_i2c_addr(&mut i2c_master).map_err(ConstructorError::AddrDetectionError)?; + Lis2dh12::new(i2c_master, slave_addr).map_err(ConstructorError::AccelerometerError) + } + + pub fn new_with_i2cm( + i2c: I2cMaster, + addr: lis2dh12::SlaveAddr, + ) -> Result> { + Lis2dh12::new(i2c, addr) + } +} diff --git a/vscode/launch.json b/vscode/launch.json index a09cc7d..c2763cc 100644 --- a/vscode/launch.json +++ b/vscode/launch.json @@ -24,6 +24,7 @@ "runToEntryPoint": "main", "rttConfig": { "enabled": true, + // Have to use exact address unfortunately. "auto" does not work for some reason.. "address": "0x1fff8000", "decoders": [ { @@ -53,6 +54,7 @@ "runToEntryPoint": "main", "rttConfig": { "enabled": true, + // Have to use exact address unfortunately. "auto" does not work for some reason.. "address": "0x1fff8000", "decoders": [ { @@ -82,6 +84,7 @@ "runToEntryPoint": "main", "rttConfig": { "enabled": true, + // Have to use exact address unfortunately. "auto" does not work for some reason.. "address": "0x1fff8000", "decoders": [ { @@ -111,6 +114,7 @@ "runToEntryPoint": "main", "rttConfig": { "enabled": true, + // Have to use exact address unfortunately. "auto" does not work for some reason.. "address": "0x1fff8000", "decoders": [ { @@ -140,6 +144,7 @@ "runToEntryPoint": "main", "rttConfig": { "enabled": true, + // Have to use exact address unfortunately. "auto" does not work for some reason.. "address": "0x1fff8000", "decoders": [ { @@ -149,5 +154,36 @@ ] } }, + { + "type": "cortex-debug", + "request": "launch", + "name": "Debug Timer/Ticks Example", + "servertype": "jlink", + "jlinkscript": "${workspaceFolder}/jlink/JLinkSettings.JLinkScript", + "cwd": "${workspaceRoot}", + "device": "Cortex-M4", + "svdFile": "${workspaceFolder}/va416xx/svd/va416xx.svd.patched", + "preLaunchTask": "timer-ticks-example", + "overrideLaunchCommands": [ + "monitor halt", + "monitor reset", + "load", + ], + "executable": "${workspaceFolder}/target/thumbv7em-none-eabihf/debug/examples/timer-ticks", + "interface": "swd", + "runToEntryPoint": "main", + "rttConfig": { + "enabled": true, + // Have to use exact address unfortunately. "auto" does not work for some reason.. + "address": "0x1fff8000", + "decoders": [ + { + "port": 0, + "timestamp": true, + "type": "console" + } + ] + } + }, ] } \ No newline at end of file