updates for APIs

This commit is contained in:
Robin Müller 2025-04-24 12:41:37 +02:00
parent 75a339222b
commit 1071acf328
Signed by: muellerr
GPG Key ID: A649FB78196E3849
26 changed files with 64 additions and 370 deletions

View File

@ -10,7 +10,7 @@ use num_enum::TryFromPrimitive;
use panic_probe as _;
// Import logger.
use defmt_rtt as _;
use va108xx_hal::{pac, time::Hertz, timer::CountdownTimer};
use va108xx_hal::{pac, spi::SpiClkConfig, time::Hertz, timer::CountdownTimer};
use vorago_reb1::m95m01::M95M01;
// Useful for debugging and see what the bootloader is doing. Enabled currently, because
@ -104,9 +104,10 @@ fn main() -> ! {
}
let dp = pac::Peripherals::take().unwrap();
let cp = cortex_m::Peripherals::take().unwrap();
let mut timer = CountdownTimer::new(CLOCK_FREQ, dp.tim0);
let mut timer = CountdownTimer::new(dp.tim0, CLOCK_FREQ);
let mut nvm = M95M01::new(CLOCK_FREQ, dp.spic);
let clk_config = SpiClkConfig::new(2, 4);
let mut nvm = M95M01::new(dp.spic, clk_config);
if FLASH_SELF {
let mut first_four_bytes: [u8; 4] = [0; 4];

View File

@ -72,9 +72,10 @@ async fn main(spawner: Spawner) {
let rx_uart_a = porta.pa8;
let uarta = uart::Uart::new_with_interrupt(
50.MHz(),
dp.uarta,
(tx_uart_a, rx_uart_a),
tx_uart_a,
rx_uart_a,
50.MHz(),
115200.Hz().into(),
InterruptConfig::new(pac::Interrupt::OC2, true, true),
)
@ -84,9 +85,10 @@ async fn main(spawner: Spawner) {
let rx_uart_b = porta.pa2;
let uartb = uart::Uart::new_with_interrupt(
50.MHz(),
dp.uartb,
(tx_uart_b, rx_uart_b),
tx_uart_b,
rx_uart_b,
50.MHz(),
115200.Hz().into(),
InterruptConfig::new(pac::Interrupt::OC3, true, true),
)

View File

@ -60,9 +60,10 @@ async fn main(_spawner: Spawner) {
let rx = porta.pa8;
let uarta = uart::Uart::new_with_interrupt(
50.MHz(),
dp.uarta,
(tx, rx),
tx,
rx,
50.MHz(),
115200.Hz().into(),
InterruptConfig::new(pac::Interrupt::OC2, true, true),
)

View File

@ -54,9 +54,10 @@ mod app {
let rx = gpioa.pa8;
let irq_uart = uart::Uart::new_with_interrupt(
SYSCLK_FREQ,
dp.uarta,
(tx, rx),
tx,
rx,
SYSCLK_FREQ,
115200.Hz().into(),
InterruptConfig::new(pac::Interrupt::OC3, true, true),
)

View File

@ -20,7 +20,7 @@ use va108xx_hal::{
#[entry]
fn main() -> ! {
let dp = pac::Peripherals::take().unwrap();
let mut delay = CountdownTimer::new(50.MHz(), dp.tim1);
let mut delay = CountdownTimer::new(dp.tim1, 50.MHz());
let porta = PinsA::new(dp.porta);
let mut led1 = Output::new(porta.pa10, PinState::Low);
let mut led2 = Output::new(porta.pa7, PinState::Low);

View File

@ -23,16 +23,16 @@ fn main() -> ! {
defmt::println!("-- VA108xx Cascade example application--");
let dp = pac::Peripherals::take().unwrap();
let mut delay = CountdownTimer::new(50.MHz(), dp.tim0);
let mut delay = CountdownTimer::new(dp.tim0, 50.MHz());
// Will be started periodically to trigger a cascade
let mut cascade_triggerer = CountdownTimer::new(50.MHz(), dp.tim3);
let mut cascade_triggerer = CountdownTimer::new(dp.tim3, 50.MHz());
cascade_triggerer.auto_disable(true);
cascade_triggerer.enable_interrupt(InterruptConfig::new(pac::Interrupt::OC1, true, false));
cascade_triggerer.enable();
// First target for cascade
let mut cascade_target_1 = CountdownTimer::new(50.MHz(), dp.tim4);
let mut cascade_target_1 = CountdownTimer::new(dp.tim4, 50.MHz());
cascade_target_1.auto_deactivate(true);
cascade_target_1
.cascade_source(CascadeSelect::Csd0, CascadeSource::Tim(3))
@ -52,7 +52,7 @@ fn main() -> ! {
cascade_target_1.start(1.Hz());
// Activated by first cascade target
let mut cascade_target_2 = CountdownTimer::new(50.MHz(), dp.tim5);
let mut cascade_target_2 = CountdownTimer::new(dp.tim5, 50.MHz());
cascade_target_2.auto_deactivate(true);
// Set TIM4 as cascade source
cascade_target_2

View File

@ -23,8 +23,8 @@ fn main() -> ! {
defmt::println!("-- VA108xx PWM example application--");
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 pwm = pwm::PwmPin::new(pinsa.pa3, dp.tim3, 50.MHz(), 10.Hz()).unwrap();
let mut delay = CountdownTimer::new(dp.tim0, 50.MHz());
let mut current_duty_cycle = 0.0;
pwm.set_duty_cycle(get_duty_from_percent(current_duty_cycle))
.unwrap();

View File

@ -43,7 +43,7 @@ const FILL_WORD: u8 = 0x0f;
fn main() -> ! {
defmt::println!("-- VA108xx SPI example application--");
let dp = pac::Peripherals::take().unwrap();
let mut delay = CountdownTimer::new(50.MHz(), dp.tim0);
let mut delay = CountdownTimer::new(dp.tim0, 50.MHz());
let spi_clk_cfg = SpiClkConfig::from_clk(50.MHz(), SPI_SPEED_KHZ.kHz())
.expect("creating SPI clock config failed");
@ -59,19 +59,19 @@ fn main() -> ! {
let mut spi = match SPI_BUS_SEL {
SpiBusSelect::SpiAPortA => {
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();
let mut spia = Spi::new(dp.spia, (sck, miso, mosi), spi_cfg).unwrap();
spia.set_fill_word(FILL_WORD);
spia
}
SpiBusSelect::SpiAPortB => {
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();
let mut spia = Spi::new(dp.spia, (sck, miso, mosi), spi_cfg).unwrap();
spia.set_fill_word(FILL_WORD);
spia
}
SpiBusSelect::SpiBPortB => {
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();
let mut spib = Spi::new(dp.spib, (sck, miso, mosi), spi_cfg).unwrap();
spib.set_fill_word(FILL_WORD);
spib
}

View File

@ -29,7 +29,7 @@ static SEC_COUNTER: AtomicU32 = AtomicU32::new(0);
#[entry]
fn main() -> ! {
let dp = pac::Peripherals::take().unwrap();
let mut delay = CountdownTimer::new(50.MHz(), dp.tim2);
let mut delay = CountdownTimer::new(dp.tim2, 50.MHz());
let mut last_ms = 0;
defmt::info!("-- Vorago system ticks using timers --");
set_sys_clock(50.MHz());
@ -67,10 +67,10 @@ fn main() -> ! {
}
}
LibType::Hal => {
let mut ms_timer = CountdownTimer::new(get_sys_clock().unwrap(), dp.tim0);
let mut ms_timer = CountdownTimer::new(dp.tim0, get_sys_clock().unwrap());
ms_timer.enable_interrupt(InterruptConfig::new(interrupt::OC0, true, true));
ms_timer.start(1.kHz());
let mut second_timer = CountdownTimer::new(get_sys_clock().unwrap(), dp.tim1);
let mut second_timer = CountdownTimer::new(dp.tim1, get_sys_clock().unwrap());
second_timer.enable_interrupt(InterruptConfig::new(interrupt::OC1, true, true));
second_timer.start(1.Hz());
}

View File

@ -28,8 +28,8 @@ fn main() -> ! {
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 uart =
uart::Uart::new_without_interrupt(dp.uarta, tx, rx, 50.MHz(), 115200.Hz().into()).unwrap();
let (mut tx, mut rx) = uart.split();
writeln!(tx, "Hello World\r").unwrap();

View File

@ -113,9 +113,10 @@ mod app {
let rx = gpioa.pa8;
let irq_uart = uart::Uart::new_with_interrupt(
SYSCLK_FREQ,
dp.uarta,
(tx, rx),
tx,
rx,
SYSCLK_FREQ,
UART_BAUDRATE.Hz().into(),
InterruptConfig::new(pac::Interrupt::OC0, true, true),
)

View File

@ -11,21 +11,8 @@ keywords = ["no-std", "hal", "cortex-m", "vorago", "va108xx"]
categories = ["aerospace", "embedded", "no-std", "hardware-support"]
[dependencies]
critical-section = "1"
embassy-sync = "0.6"
embassy-executor = "0.7"
embassy-time-driver = "0.2"
embassy-time-queue-utils = "0.1"
once_cell = { version = "1", default-features = false, features = ["critical-section"] }
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"] }
[target.'cfg(not(all(target_arch = "arm", target_os = "none")))'.dependencies]
portable-atomic = "1"
vorago-shared-periphs = { version = "0.1", path = "../../vorago-shared-periphs" }
va108xx-hal = { path = "../va108xx-hal" }
[features]
default = ["irq-oc30-oc31"]

View File

@ -32,33 +32,12 @@
//! [embassy example projects](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples/embassy)
#![no_std]
#![cfg_attr(docsrs, feature(doc_auto_cfg))]
use core::cell::{Cell, RefCell};
use critical_section::{CriticalSection, Mutex};
use portable_atomic::{AtomicU32, Ordering};
use embassy_time_driver::{time_driver_impl, Driver, TICK_HZ};
use embassy_time_queue_utils::Queue;
use once_cell::sync::OnceCell;
#[cfg(feature = "irqs-in-lib")]
use va108xx_hal::pac::interrupt;
use va108xx_hal::{
clock::enable_peripheral_clock,
enable_nvic_interrupt, pac,
prelude::*,
timer::{
enable_tim_clk,
regs::{EnableControl, MmioTimer},
TimId, TimMarker,
},
PeripheralSelect,
};
time_driver_impl!(
static TIME_DRIVER: TimerDriver = TimerDriver {
periods: AtomicU32::new(0),
alarms: Mutex::new(AlarmState::new()),
queue: Mutex::new(RefCell::new(Queue::new())),
});
use va108xx_hal::pac::{self, interrupt};
use va108xx_hal::time::Hertz;
use va108xx_hal::timer::TimMarker;
use vorago_shared_periphs::embassy::time_driver;
/// Macro to define the IRQ handlers for the time driver.
///
@ -103,11 +82,6 @@ embassy_time_driver_irqs!(timekeeper_irq = OC30, alarm_irq = OC29);
#[cfg(feature = "irq-oc28-oc29")]
embassy_time_driver_irqs!(timekeeper_irq = OC29, alarm_irq = OC28);
/// Expose the time driver so the user can specify the IRQ handlers themselves.
pub fn time_driver() -> &'static TimerDriver {
&TIME_DRIVER
}
/// Initialization method for embassy.
///
/// This should be used if the interrupt handler is provided by the library, which is the
@ -118,7 +92,7 @@ pub fn init<TimekeeperTim: TimMarker, AlarmTim: TimMarker>(
timekeeper_tim: TimekeeperTim,
alarm_tim: AlarmTim,
) {
TIME_DRIVER.init(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.
@ -131,258 +105,5 @@ pub fn init_with_custom_irqs<TimekeeperTim: TimMarker, AlarmTim: TimMarker>(
timekeeper_irq: pac::Interrupt,
alarm_irq: pac::Interrupt,
) {
TIME_DRIVER.init(sysclk, timekeeper_tim, alarm_tim, timekeeper_irq, alarm_irq)
}
struct AlarmState {
timestamp: Cell<u64>,
}
impl AlarmState {
const fn new() -> Self {
Self {
timestamp: Cell::new(u64::MAX),
}
}
}
unsafe impl Send for AlarmState {}
static SCALE: OnceCell<u64> = OnceCell::new();
static TIMEKEEPER_TIM: OnceCell<TimId> = OnceCell::new();
static ALARM_TIM: OnceCell<TimId> = OnceCell::new();
pub struct TimerDriver {
periods: AtomicU32,
/// Timestamp at which to fire alarm. u64::MAX if no alarm is scheduled.
alarms: Mutex<AlarmState>,
queue: Mutex<RefCell<Queue>>,
}
impl TimerDriver {
#[allow(clippy::too_many_arguments)]
fn init<TimekeeperTim: TimMarker, AlarmTim: TimMarker>(
&self,
sysclk: Hertz,
_timekeeper_tim: TimekeeperTim,
_alarm_tim: AlarmTim,
timekeeper_irq: pac::Interrupt,
alarm_irq: pac::Interrupt,
) {
if ALARM_TIM.get().is_some() || TIMEKEEPER_TIM.get().is_some() {
return;
}
ALARM_TIM.set(AlarmTim::ID).ok();
TIMEKEEPER_TIM.set(TimekeeperTim::ID).ok();
enable_peripheral_clock(PeripheralSelect::Irqsel);
enable_tim_clk(TimekeeperTim::ID);
let mut timekeeper_reg_block = unsafe { TimekeeperTim::ID.steal_regs() };
let mut alarm_tim_reg_block = unsafe { AlarmTim::ID.steal_regs() };
// 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.write_reset_value(u32::MAX);
// Decrementing counter.
timekeeper_reg_block.write_count_value(u32::MAX);
let irqsel = unsafe { va108xx_hal::pac::Irqsel::steal() };
// Switch on. Timekeeping should always be done.
irqsel
.tim0(TimekeeperTim::ID.value() as usize)
.write(|w| unsafe { w.bits(timekeeper_irq as u32) });
unsafe {
enable_nvic_interrupt(timekeeper_irq);
}
timekeeper_reg_block.modify_control(|mut value| {
value.set_irq_enable(true);
value
});
timekeeper_reg_block.write_enable_control(EnableControl::new_enable());
enable_tim_clk(AlarmTim::ID);
// Explicitely disable alarm timer until needed.
alarm_tim_reg_block.modify_control(|mut value| {
value.set_irq_enable(false);
value.set_enable(false);
value
});
// Enable general interrupts. The IRQ enable of the peripheral remains cleared.
unsafe {
enable_nvic_interrupt(alarm_irq);
}
irqsel
.tim0(AlarmTim::ID.value() as usize)
.write(|w| unsafe { w.bits(alarm_irq as u32) });
}
/// Should be called inside the IRQ of the timekeeper timer.
///
/// # Safety
///
/// This function has to be called once by the TIM IRQ used for the timekeeping.
pub unsafe fn on_interrupt_timekeeping(&self) {
self.next_period();
}
/// Should be called inside the IRQ of the alarm timer.
///
/// # Safety
///
///This function has to be called once by the TIM IRQ used for the timekeeping.
pub unsafe fn on_interrupt_alarm(&self) {
critical_section::with(|cs| {
if self.alarms.borrow(cs).timestamp.get() <= self.now() {
self.trigger_alarm(cs)
}
})
}
fn timekeeper_tim() -> MmioTimer<'static> {
TIMEKEEPER_TIM
.get()
.map(|id| unsafe { id.steal_regs() })
.unwrap()
}
fn alarm_tim() -> MmioTimer<'static> {
ALARM_TIM
.get()
.map(|id| unsafe { id.steal_regs() })
.unwrap()
}
fn next_period(&self) {
let period = self.periods.fetch_add(1, Ordering::AcqRel) + 1;
let t = (period as u64) << 32;
critical_section::with(|cs| {
let alarm = &self.alarms.borrow(cs);
let at = alarm.timestamp.get();
if at < t {
self.trigger_alarm(cs);
} else {
let mut alarm_tim = Self::alarm_tim();
let remaining_ticks = (at - t).checked_mul(*SCALE.get().unwrap());
if remaining_ticks.is_some_and(|v| v <= u32::MAX as u64) {
alarm_tim.write_enable_control(EnableControl::new_disable());
alarm_tim.write_count_value(remaining_ticks.unwrap() as u32);
alarm_tim.modify_control(|mut value| {
value.set_irq_enable(true);
value
});
alarm_tim.write_enable_control(EnableControl::new_enable());
}
}
})
}
fn trigger_alarm(&self, cs: CriticalSection) {
Self::alarm_tim().modify_control(|mut value| {
value.set_irq_enable(false);
value.set_enable(false);
value
});
let alarm = &self.alarms.borrow(cs);
// Setting the maximum value disables the alarm.
alarm.timestamp.set(u64::MAX);
// Call after clearing alarm, so the callback can set another alarm.
let mut next = self
.queue
.borrow(cs)
.borrow_mut()
.next_expiration(self.now());
while !self.set_alarm(cs, next) {
next = self
.queue
.borrow(cs)
.borrow_mut()
.next_expiration(self.now());
}
}
fn set_alarm(&self, cs: CriticalSection, timestamp: u64) -> bool {
if SCALE.get().is_none() {
return false;
}
let mut alarm_tim = Self::alarm_tim();
alarm_tim.modify_control(|mut value| {
value.set_irq_enable(false);
value.set_enable(false);
value
});
let alarm = self.alarms.borrow(cs);
alarm.timestamp.set(timestamp);
let t = self.now();
if timestamp <= t {
alarm.timestamp.set(u64::MAX);
return false;
}
// If it hasn't triggered yet, setup the relevant reset value, regardless of whether
// the interrupts are enabled or not. When they are enabled at a later point, the
// right value is already set.
// If the timestamp is in the next few ticks, add a bit of buffer to be sure the alarm
// is not missed.
//
// This means that an alarm can be delayed for up to 2 ticks (from t+1 to t+3), but this is allowed
// by the Alarm trait contract. What's not allowed is triggering alarms *before* their scheduled time,
// and we don't do that here.
let safe_timestamp = timestamp.max(t + 3);
let timer_ticks = (safe_timestamp - t).checked_mul(*SCALE.get().unwrap());
alarm_tim.write_reset_value(u32::MAX);
if timer_ticks.is_some_and(|v| v <= u32::MAX as u64) {
alarm_tim.write_count_value(timer_ticks.unwrap() as u32);
alarm_tim.modify_control(|mut value| {
value.set_irq_enable(true);
value.set_enable(true);
value
});
}
// If it's too far in the future, don't enable timer yet.
// It will be enabled later by `next_period`.
true
}
}
impl Driver for TimerDriver {
fn now(&self) -> u64 {
if SCALE.get().is_none() {
return 0;
}
let mut period1: u32;
let mut period2: u32;
let mut counter_val: u32;
loop {
// Acquire ensures that we get the latest value of `periods` and
// no instructions can be reordered before the load.
period1 = self.periods.load(Ordering::Acquire);
counter_val = u32::MAX - Self::timekeeper_tim().read_count_value();
// Double read to protect against race conditions when the counter is overflowing.
period2 = self.periods.load(Ordering::Relaxed);
if period1 == period2 {
let now = (((period1 as u64) << 32) | counter_val as u64) / *SCALE.get().unwrap();
return now;
}
}
}
fn schedule_wake(&self, at: u64, waker: &core::task::Waker) {
critical_section::with(|cs| {
let mut queue = self.queue.borrow(cs).borrow_mut();
if queue.schedule_wake(at, waker) {
let mut next = queue.next_expiration(self.now());
while !self.set_alarm(cs, next) {
next = queue.next_expiration(self.now());
}
}
})
}
time_driver().__init(sysclk, timekeeper_tim, alarm_tim, timekeeper_irq, alarm_irq)
}

View File

@ -15,7 +15,8 @@ cortex-m = { version = "0.7", features = ["critical-section-single-core"]}
cortex-m-rt = "0.7"
nb = "1"
paste = "1"
vorago-shared-periphs = { git = "https://egit.irs.uni-stuttgart.de/rust/vorago-shared-periphs.git", features = ["vor1x"] }
#vorago-shared-periphs = { git = "https://egit.irs.uni-stuttgart.de/rust/vorago-shared-periphs.git", features = ["vor1x"] }
vorago-shared-periphs = { path = "../../vorago-shared-periphs", features = ["vor1x"] }
embedded-hal = "1"
embedded-hal-async = "1"
embedded-hal-nb = "1"

View File

@ -18,10 +18,3 @@
//! - [Blinky example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples/simple/examples/blinky.rs)
//! - [Async GPIO example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples/embassy/src/bin/async-gpio.rs)
pub use vorago_shared_periphs::gpio::*;
pub use vorago_shared_periphs::gpio::asynch;
/// Low-level GPIO access.
pub use vorago_shared_periphs::gpio::ll;
/// GPIO register definitions.
pub use vorago_shared_periphs::gpio::regs;

View File

@ -17,15 +17,13 @@ pub mod time;
pub mod timer;
pub mod uart;
pub use vorago_shared_periphs::FunSel;
pub use vorago_shared_periphs::{
disable_nvic_interrupt, enable_nvic_interrupt, FunSel, InterruptConfig, PeripheralSelect,
};
/// This is the NONE destination reigster value for the IRQSEL peripheral.
pub const IRQ_DST_NONE: u32 = 0xffffffff;
pub use vorago_shared_periphs::{
disable_nvic_interrupt, enable_nvic_interrupt, InterruptConfig, PeripheralSelect,
};
#[derive(Debug, PartialEq, Eq, thiserror::Error)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
#[error("invalid pin with number {0}")]

View File

@ -10,5 +10,3 @@
//! - [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)
pub use vorago_shared_periphs::spi::*;
pub use vorago_shared_periphs::spi::pins_vor1x as pins;

View File

@ -5,5 +5,3 @@
//! - [MS and second tick implementation](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples/simple/examples/timer-ticks.rs)
//! - [Cascade feature example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples/simple/examples/cascade.rs)
pub use vorago_shared_periphs::timer::*;
pub use vorago_shared_periphs::timer::regs;

View File

@ -15,6 +15,3 @@
//! - [Async UART RX example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples/embassy/src/bin/async-uart-rx.rs)
//! - [Async UART TX example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples/embassy/src/bin/async-uart-tx.rs)
pub use vorago_shared_periphs::uart::*;
pub use vorago_shared_periphs::uart::rx_asynch;
pub use vorago_shared_periphs::uart::tx_asynch;

View File

@ -12,7 +12,7 @@ fn main() -> ! {
rtt_init_print!();
rprintln!("-- Vorago Temperature Sensor and I2C Example --");
let dp = pac::Peripherals::take().unwrap();
let mut delay = CountdownTimer::new(50.MHz(), dp.tim0);
let mut delay = CountdownTimer::new(dp.tim0, 50.MHz());
let mut temp_sensor =
Adt75TempSensor::new(50.MHz(), dp.i2ca).expect("Creating temperature sensor struct failed");
loop {

View File

@ -32,7 +32,7 @@ fn main() -> ! {
rprintln!("-- Vorago Accelerometer Example --");
let dp = pac::Peripherals::take().unwrap();
let pinsa = PinsA::new(dp.porta);
let mut delay = CountdownTimer::new(50.MHz(), dp.tim0);
let mut delay = CountdownTimer::new(dp.tim0, 50.MHz());
let (sck, mosi, miso) = (pinsa.pa20, pinsa.pa19, pinsa.pa18);
let cs_pin = pinsa.pa16;
let hw_cs_id = configure_pin_as_hw_cs_pin(cs_pin);
@ -46,7 +46,7 @@ fn main() -> ! {
)
.mode(MODE_3)
.slave_output_disable(true);
let mut spi = Spi::new(50.MHz(), dp.spib, (sck, miso, mosi), spi_cfg).unwrap();
let mut spi = Spi::new(dp.spib, (sck, miso, mosi), spi_cfg).unwrap();
spi.cfg_hw_cs(hw_cs_id);
let mut tx_rx_buf: [u8; 3] = [0; 3];

View File

@ -70,7 +70,7 @@ fn main() -> ! {
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);
let mut delay = CountdownTimer::new(dp.tim0, 50.MHz());
for _ in 0..10 {
led1.set_low();
led2.set_low();
@ -91,7 +91,7 @@ fn main() -> ! {
LibType::Bsp => {
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);
let mut delay = CountdownTimer::new(dp.tim0, 50.MHz());
for _ in 0..10 {
// Blink all LEDs quickly
for led in leds.iter_mut() {

View File

@ -110,7 +110,7 @@ fn main() -> ! {
rprintln!("-- Vorago ADC Example --");
let mut dp = pac::Peripherals::take().unwrap();
let mut delay = CountdownTimer::new(SYS_CLK, dp.tim0);
let mut delay = CountdownTimer::new(dp.tim0, SYS_CLK);
unsafe {
cortex_m::peripheral::NVIC::unmask(pac::Interrupt::OC0);
}
@ -132,9 +132,9 @@ fn main() -> ! {
Output::new(pinsa.pa16, PinState::Low);
let hw_cs_id = configure_pin_as_hw_cs_pin(pinsa.pa17);
let spi = Spi::new(50.MHz(), dp.spib, (sck, miso, mosi), spi_cfg).unwrap();
let spi = Spi::new(dp.spib, (sck, miso, mosi), spi_cfg).unwrap();
let delay_spi = CountdownTimer::new(SYS_CLK, dp.tim1);
let delay_spi = CountdownTimer::new(dp.tim1, SYS_CLK);
let spi_with_hwcs = SpiWithHwCs::new(spi, hw_cs_id, delay_spi);
match EXAMPLE_MODE {
ExampleMode::NotUsingEoc => spi_example_externally_clocked(spi_with_hwcs, &mut delay),

View File

@ -5,7 +5,7 @@ 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, time::Hertz, timer::CountdownTimer};
use va108xx_hal::{pac, spi::SpiClkConfig, time::Hertz, timer::CountdownTimer};
use vorago_reb1::m95m01::{M95M01, PAGE_SIZE};
const CLOCK_FREQ: Hertz = Hertz::from_raw(50_000_000);
@ -17,8 +17,9 @@ fn main() -> ! {
let dp = pac::Peripherals::take().unwrap();
let mut timer = CountdownTimer::new(CLOCK_FREQ, dp.tim0);
let mut nvm = M95M01::new(CLOCK_FREQ, dp.spic);
let mut delay = CountdownTimer::new(dp.tim0, CLOCK_FREQ);
let clk_config = SpiClkConfig::new(2, 4);
let mut nvm = M95M01::new(dp.spic, clk_config);
let status_reg = nvm.read_status_reg().expect("reading status reg failed");
if status_reg.zero_segment().value() == 0b111 {
panic!("status register unexpected values");
@ -51,6 +52,6 @@ fn main() -> ! {
nvm.write(0, &orig_content).unwrap();
loop {
timer.delay_ms(500);
delay.delay_ms(500);
}
}

View File

@ -47,7 +47,6 @@ pub mod regs {
use regs::*;
use va108xx_hal::{
pac,
prelude::*,
spi::{Spi, SpiClkConfig, SpiConfig, SpiLowLevel, BMSTART_BMSTOP_MASK},
};
@ -64,13 +63,8 @@ pub struct M95M01 {
pub struct PageBoundaryExceededError;
impl M95M01 {
pub fn new(sys_clk: Hertz, spi: pac::Spic) -> Self {
let spi = RomSpi::new_for_rom(
sys_clk,
spi,
SpiConfig::default().clk_cfg(SpiClkConfig::new(2, 4)),
)
.unwrap();
pub fn new(spi: pac::Spic, clk_config: SpiClkConfig) -> Self {
let spi = RomSpi::new_for_rom(spi, SpiConfig::default().clk_cfg(clk_config)).unwrap();
let mut spi_dev = Self { spi };
spi_dev.clear_block_protection().unwrap();
spi_dev

View File

@ -52,8 +52,8 @@ impl Adt75TempSensor {
let mut sensor = Adt75TempSensor {
// The master construction can not fail for regular I2C speed.
sensor_if: I2cMaster::new(
sys_clk,
i2ca,
sys_clk,
MasterConfig::default(),
I2cSpeed::Regular100khz,
)