update package
All checks were successful
Rust/va108xx-rs/pipeline/pr-main This commit looks good

- Add embassy example
- improve timer API
- restructure examples
This commit is contained in:
Robin Müller 2024-09-18 15:07:29 +02:00
parent 405cc089c3
commit 4bf50bfa88
27 changed files with 787 additions and 184 deletions

View File

@ -39,7 +39,9 @@ jobs:
steps: steps:
- uses: actions/checkout@v4 - uses: actions/checkout@v4
- uses: dtolnay/rust-toolchain@nightly - uses: dtolnay/rust-toolchain@nightly
- run: RUSTDOCFLAGS="--cfg docsrs --generate-link-to-definition -Z unstable-options" cargo +nightly doc --all-features - run: RUSTDOCFLAGS="--cfg docsrs --generate-link-to-definition -Z unstable-options" cargo +nightly doc -p va108xx
- run: RUSTDOCFLAGS="--cfg docsrs --generate-link-to-definition -Z unstable-options" cargo +nightly doc -p va108xx-hal
- run: RUSTDOCFLAGS="--cfg docsrs --generate-link-to-definition -Z unstable-options" cargo +nightly doc -p vorago-reb1
clippy: clippy:
name: Clippy name: Clippy

View File

@ -5,6 +5,8 @@ members = [
"va108xx", "va108xx",
"va108xx-hal", "va108xx-hal",
"examples/simple", "examples/simple",
"examples/rtic",
"examples/embassy",
"board-tests", "board-tests",
] ]

View File

@ -19,9 +19,13 @@ This workspace contains the following released crates:
It also contains the following helper crates: It also contains the following helper crates:
- The `board-tests` contains an application which can be used to test the libraries on the - The [`board-tests`](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/board-tests)
board. contains an application which can be used to test the libraries on the board.
- The `examples` crates contains various example applications for the HAL and the PAC. - The [`examples`](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples)
folder contains various example applications crates using the HAL and the PAC.
This folder also contains dedicated example applications using the
[`RTIC`](https://rtic.rs/2/book/en/) and [`embassy`](https://github.com/embassy-rs/embassy)
native Rust RTOSes.
## Using the `.cargo/config.toml` file ## Using the `.cargo/config.toml` file
@ -94,6 +98,8 @@ example.
Assuming a working debug connection to your VA108xx board, you can debug using VS Code with Assuming a working debug connection to your VA108xx board, you can debug using VS Code with
the [`Cortex-Debug` plugin](https://marketplace.visualstudio.com/items?itemName=marus25.cortex-debug). the [`Cortex-Debug` plugin](https://marketplace.visualstudio.com/items?itemName=marus25.cortex-debug).
Please make sure that [`objdump-multiarch` and `nm-multiarch`](https://forums.raspberrypi.com/viewtopic.php?t=333146)
are installed as well.
Some sample configuration files for VS code were provided and can be used by running Some sample configuration files for VS code were provided and can be used by running
`cp -rT vscode .vscode` like specified above. After that, you can use `Run and Debug` `cp -rT vscode .vscode` like specified above. After that, you can use `Run and Debug`
@ -108,4 +114,5 @@ configuration variables in your `settings.json`:
- `"cortex-debug.gdbPath.osx"` - `"cortex-debug.gdbPath.osx"`
The provided VS Code configurations also provide an integrated RTT logger, which you can access The provided VS Code configurations also provide an integrated RTT logger, which you can access
via the terminal at `RTT Ch:0 console`. via the terminal at `RTT Ch:0 console`. In order for the RTT block address detection to
work properly, `objdump-multiarch` and `nm-multiarch` need to be installed.

View File

@ -25,7 +25,9 @@ pipeline {
stage('Docs') { stage('Docs') {
steps { steps {
sh """ sh """
RUSTDOCFLAGS="--cfg docsrs --generate-link-to-definition -Z unstable-options" cargo +nightly doc --all-features RUSTDOCFLAGS="--cfg docsrs --generate-link-to-definition -Z unstable-options" cargo +nightly doc -p va108xx
RUSTDOCFLAGS="--cfg docsrs --generate-link-to-definition -Z unstable-options" cargo +nightly doc -p va108xx-hal
RUSTDOCFLAGS="--cfg docsrs --generate-link-to-definition -Z unstable-options" cargo +nightly doc -p vorago-reb1
""" """
} }
} }

View File

@ -4,10 +4,9 @@ version = "0.1.0"
edition = "2021" edition = "2021"
[dependencies] [dependencies]
cortex-m-rtic = "1"
panic-halt = "0.2"
cortex-m = { version = "0.7.6", features = ["critical-section-single-core"] } cortex-m = { version = "0.7.6", features = ["critical-section-single-core"] }
cortex-m-rt = "0.7" cortex-m-rt = "0.7"
panic-halt = "0.2"
rtt-target = "0.5" rtt-target = "0.5"
panic-rtt-target = "0.1.3" panic-rtt-target = "0.1.3"
embedded-hal = "1" embedded-hal = "1"

25
examples/README.md Normal file
View File

@ -0,0 +1,25 @@
VA108xx Example Applications
========
This folder contains various examples
Consult the main README first for setup of the repository.
## Simple examples
```rs
cargo run --example blinky
```
You can have a look at the `simple/examples` folder to see all available simple examples
## RTIC example
```rs
cargo run --bin rtic-example
```
## Embassy example
```rs
cargo run --bin embassy-example
```

View File

@ -0,0 +1,40 @@
[package]
name = "embassy-example"
version = "0.1.0"
edition = "2021"
[dependencies]
cortex-m = { version = "0.7", features = ["critical-section-single-core"] }
cortex-m-rt = "0.7"
embedded-hal = "1"
rtt-target = { version = "0.5" }
panic-rtt-target = { version = "0.1" }
critical-section = "1"
portable-atomic = { version = "1", features = ["unsafe-assume-single-core"]}
embassy-sync = { version = "0.6.0" }
embassy-time = { version = "0.3.2" }
embassy-time-driver = { version = "0.1" }
[dependencies.once_cell]
version = "1"
default-features = false
features = ["critical-section"]
[dependencies.embassy-executor]
version = "0.6.0"
features = [
"arch-cortex-m",
"executor-thread",
"executor-interrupt",
"integrated-timers",
]
[dependencies.va108xx-hal]
path = "../../va108xx-hal"
[features]
default = ["ticks-hz-1_000"]
ticks-hz-1_000 = ["embassy-time/tick-hz-1_000"]
ticks-hz-32_768 = ["embassy-time/tick-hz-32_768"]

View File

@ -0,0 +1,4 @@
#![no_std]
pub mod time_driver;
pub use time_driver::init;

View File

@ -0,0 +1,43 @@
#![no_std]
#![no_main]
use embassy_executor::Spawner;
use embassy_time::{Duration, Instant, Ticker};
use embedded_hal::digital::StatefulOutputPin;
use panic_rtt_target as _;
use rtt_target::{rprintln, rtt_init_print};
use va108xx_hal::{gpio::PinsA, pac, prelude::*};
const SYSCLK_FREQ: Hertz = Hertz::from_raw(50_000_000);
// main is itself an async function.
#[embassy_executor::main]
async fn main(_spawner: Spawner) {
rtt_init_print!();
rprintln!("-- VA108xx Embassy Demo --");
let mut dp = pac::Peripherals::take().unwrap();
// Safety: Only called once here.
unsafe {
embassy_example::init(
&mut dp.sysconfig,
&dp.irqsel,
SYSCLK_FREQ,
dp.tim23,
dp.tim22,
)
};
let porta = PinsA::new(&mut dp.sysconfig, Some(dp.ioconfig), dp.porta);
let mut led0 = porta.pa10.into_readable_push_pull_output();
let mut led1 = porta.pa7.into_readable_push_pull_output();
let mut led2 = porta.pa6.into_readable_push_pull_output();
let mut ticker = Ticker::every(Duration::from_secs(1));
loop {
ticker.next().await;
rprintln!("Current time: {}", Instant::now().as_secs());
led0.toggle().ok();
led1.toggle().ok();
led2.toggle().ok();
}
}

View File

@ -0,0 +1,334 @@
//! This is a sample time driver implementation for the VA108xx family of devices, supporting
//! one alarm and requiring/reserving 2 TIM peripherals. You could adapt this implementation to
//! support more alarms.
//!
//! This driver implementation reserves interrupts OC31 and OC30 for the timekeeping.
use core::{cell::Cell, mem, ptr};
use critical_section::CriticalSection;
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
use embassy_sync::blocking_mutex::Mutex;
use portable_atomic::{AtomicU32, AtomicU8, Ordering};
use embassy_time_driver::{time_driver_impl, AlarmHandle, Driver, TICK_HZ};
use once_cell::sync::OnceCell;
use va108xx_hal::{
clock::enable_peripheral_clock,
enable_interrupt,
pac::{self, interrupt},
prelude::*,
timer::{enable_tim_clk, ValidTim},
PeripheralSelect,
};
pub type TimekeeperClk = pac::Tim23;
pub type AlarmClk0 = pac::Tim22;
pub type AlarmClk1 = pac::Tim21;
pub type AlarmClk2 = pac::Tim20;
const TIMEKEEPER_IRQ: pac::Interrupt = pac::Interrupt::OC31;
const ALARM_IRQ: pac::Interrupt = pac::Interrupt::OC30;
/// Initialization method for embassy
///
/// # Safety
/// This has to be called once at initialization time to initiate the time driver for
/// embassy.
pub unsafe fn init(
syscfg: &mut pac::Sysconfig,
irqsel: &pac::Irqsel,
sysclk: impl Into<Hertz>,
timekeeper: TimekeeperClk,
alarm_tim: AlarmClk0,
) {
//enable_and_init_irq_router(syscfg, irq_router);
DRIVER.init(syscfg, irqsel, sysclk, timekeeper, alarm_tim)
}
time_driver_impl!(
static DRIVER: TimerDriverEmbassy = TimerDriverEmbassy {
periods: AtomicU32::new(0),
alarm_count: AtomicU8::new(0),
alarms: Mutex::const_new(CriticalSectionRawMutex::new(), [AlarmState::new(); ALARM_COUNT])
});
/// Timekeeper interrupt.
#[interrupt]
#[allow(non_snake_case)]
fn OC31() {
DRIVER.on_interrupt_timekeeping()
}
/// Alarm timer interrupt.
#[interrupt]
#[allow(non_snake_case)]
fn OC30() {
DRIVER.on_interrupt_alarm(0)
}
#[inline(always)]
const fn alarm_tim(idx: usize) -> &'static pac::tim0::RegisterBlock {
// Safety: This is a static memory-mapped peripheral.
match idx {
0 => unsafe { &*AlarmClk0::ptr() },
1 => unsafe { &*AlarmClk1::ptr() },
2 => unsafe { &*AlarmClk2::ptr() },
_ => {
panic!("invalid alarm timer index")
}
}
}
#[inline(always)]
const fn timekeeping_tim() -> &'static pac::tim0::RegisterBlock {
// Safety: This is a memory-mapped peripheral.
unsafe { &*TimekeeperClk::ptr() }
}
struct AlarmState {
timestamp: Cell<u64>,
// This is really a Option<(fn(*mut ()), *mut ())>
// but fn pointers aren't allowed in const yet
callback: Cell<*const ()>,
ctx: Cell<*mut ()>,
}
impl AlarmState {
const fn new() -> Self {
Self {
timestamp: Cell::new(u64::MAX),
callback: Cell::new(ptr::null()),
ctx: Cell::new(ptr::null_mut()),
}
}
}
unsafe impl Send for AlarmState {}
const ALARM_COUNT: usize = 1;
static SCALE: OnceCell<u64> = OnceCell::new();
pub struct TimerDriverEmbassy {
periods: AtomicU32,
alarm_count: AtomicU8,
/// Timestamp at which to fire alarm. u64::MAX if no alarm is scheduled.
alarms: Mutex<CriticalSectionRawMutex, [AlarmState; ALARM_COUNT]>,
}
impl TimerDriverEmbassy {
fn init(
&self,
syscfg: &mut pac::Sysconfig,
irqsel: &pac::Irqsel,
sysclk: impl Into<Hertz>,
timekeeper: TimekeeperClk,
alarm_tim: AlarmClk0,
) {
enable_peripheral_clock(syscfg, PeripheralSelect::Irqsel);
enable_tim_clk(syscfg, TimekeeperClk::TIM_ID);
let sysclk = sysclk.into();
// Initiate scale value here. This is required to convert timer ticks back to a timestamp.
SCALE.set((sysclk.raw() / TICK_HZ as u32) as u64).unwrap();
timekeeper
.rst_value()
.write(|w| unsafe { w.bits(u32::MAX) });
// Decrementing counter.
timekeeper
.cnt_value()
.write(|w| unsafe { w.bits(u32::MAX) });
// Switch on. Timekeeping should always be done.
irqsel
.tim0(TimekeeperClk::TIM_ID as usize)
.write(|w| unsafe { w.bits(TIMEKEEPER_IRQ as u32) });
unsafe {
enable_interrupt(TIMEKEEPER_IRQ);
}
timekeeper.ctrl().modify(|_, w| w.irq_enb().set_bit());
timekeeper.enable().write(|w| unsafe { w.bits(1) });
enable_tim_clk(syscfg, AlarmClk0::TIM_ID);
// Explicitely disable alarm timer until needed.
alarm_tim.ctrl().modify(|_, w| {
w.irq_enb().clear_bit();
w.enable().clear_bit()
});
// Enable general interrupts. The IRQ enable of the peripheral remains cleared.
unsafe {
enable_interrupt(ALARM_IRQ);
}
irqsel
.tim0(AlarmClk0::TIM_ID as usize)
.write(|w| unsafe { w.bits(ALARM_IRQ as u32) });
}
// Should be called inside the IRQ of the timekeeper timer.
fn on_interrupt_timekeeping(&self) {
self.next_period();
}
// Should be called inside the IRQ of the alarm timer.
fn on_interrupt_alarm(&self, idx: usize) {
critical_section::with(|cs| {
if self.alarms.borrow(cs)[idx].timestamp.get() <= self.now() {
self.trigger_alarm(idx, cs)
}
})
}
fn next_period(&self) {
let period = self.periods.fetch_add(1, Ordering::AcqRel) + 1;
let t = (period as u64) << 32;
critical_section::with(|cs| {
for i in 0..ALARM_COUNT {
let alarm = &self.alarms.borrow(cs)[i];
let at = alarm.timestamp.get();
let alarm_tim = alarm_tim(0);
if at < t {
self.trigger_alarm(i, cs);
} else {
let remaining_ticks = (at - t) * *SCALE.get().unwrap();
if remaining_ticks <= u32::MAX as u64 {
alarm_tim.enable().write(|w| unsafe { w.bits(0) });
alarm_tim
.cnt_value()
.write(|w| unsafe { w.bits(remaining_ticks as u32) });
alarm_tim.ctrl().modify(|_, w| w.irq_enb().set_bit());
alarm_tim.enable().write(|w| unsafe { w.bits(1) })
}
}
}
})
}
fn get_alarm<'a>(&'a self, cs: CriticalSection<'a>, alarm: AlarmHandle) -> &'a AlarmState {
// safety: we're allowed to assume the AlarmState is created by us, and
// we never create one that's out of bounds.
unsafe { self.alarms.borrow(cs).get_unchecked(alarm.id() as usize) }
}
fn trigger_alarm(&self, n: usize, cs: CriticalSection) {
alarm_tim(n).ctrl().modify(|_, w| {
w.irq_enb().clear_bit();
w.enable().clear_bit()
});
let alarm = &self.alarms.borrow(cs)[n];
// Setting the maximum value disables the alarm.
alarm.timestamp.set(u64::MAX);
// Call after clearing alarm, so the callback can set another alarm.
// safety:
// - we can ignore the possiblity of `f` being unset (null) because of the safety contract of `allocate_alarm`.
// - other than that we only store valid function pointers into alarm.callback
let f: fn(*mut ()) = unsafe { mem::transmute(alarm.callback.get()) };
f(alarm.ctx.get());
}
}
impl Driver for TimerDriverEmbassy {
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 - timekeeping_tim().cnt_value().read().bits();
// 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;
}
}
}
unsafe fn allocate_alarm(&self) -> Option<AlarmHandle> {
let id = self
.alarm_count
.fetch_update(Ordering::AcqRel, Ordering::Acquire, |x| {
if x < ALARM_COUNT as u8 {
Some(x + 1)
} else {
None
}
});
match id {
Ok(id) => Some(AlarmHandle::new(id)),
Err(_) => None,
}
}
fn set_alarm_callback(
&self,
alarm: embassy_time_driver::AlarmHandle,
callback: fn(*mut ()),
ctx: *mut (),
) {
critical_section::with(|cs| {
let alarm = self.get_alarm(cs, alarm);
alarm.callback.set(callback as *const ());
alarm.ctx.set(ctx);
})
}
fn set_alarm(&self, alarm: embassy_time_driver::AlarmHandle, timestamp: u64) -> bool {
if SCALE.get().is_none() {
return false;
}
critical_section::with(|cs| {
let n = alarm.id();
let alarm_tim = alarm_tim(n.into());
alarm_tim.ctrl().modify(|_, w| {
w.irq_enb().clear_bit();
w.enable().clear_bit()
});
let alarm = self.get_alarm(cs, alarm);
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) * *SCALE.get().unwrap();
alarm_tim.rst_value().write(|w| unsafe { w.bits(u32::MAX) });
if timer_ticks <= u32::MAX as u64 {
alarm_tim
.cnt_value()
.write(|w| unsafe { w.bits(timer_ticks as u32) });
alarm_tim.ctrl().modify(|_, w| w.irq_enb().set_bit());
alarm_tim.enable().write(|w| unsafe { w.bits(1) });
}
// If it's too far in the future, don't enable timer yet.
// It will be enabled later by `next_period`.
true
})
}
}

30
examples/rtic/Cargo.toml Normal file
View File

@ -0,0 +1,30 @@
[package]
name = "rtic-example"
version = "0.1.0"
edition = "2021"
[dependencies]
cortex-m = { version = "0.7", features = ["critical-section-single-core"] }
cortex-m-rt = "0.7"
embedded-hal = "1"
embedded-io = "0.6"
rtt-target = { version = "0.5" }
# Even though we do not use this directly, we need to activate this feature explicitely
# so that RTIC compiles because thumv6 does not have CAS operations natively.
portable-atomic = { version = "1", features = ["unsafe-assume-single-core"]}
panic-rtt-target = { version = "0.1" }
[dependencies.va108xx-hal]
path = "../../va108xx-hal"
[dependencies.rtic]
version = "2"
features = ["thumbv6-backend"]
[dependencies.rtic-monotonics]
version = "2"
features = ["cortex-m-systick"]
[dependencies.rtic-sync]
version = "1.3"
features = ["defmt-03"]

View File

@ -14,14 +14,13 @@
mod app { mod app {
use embedded_io::Write; use embedded_io::Write;
use panic_rtt_target as _; use panic_rtt_target as _;
use rtic_monotonics::systick::Systick; use rtic_example::SYSCLK_FREQ;
use rtic_sync::make_channel; use rtic_sync::make_channel;
use rtt_target::{rprintln, rtt_init_print}; use rtt_target::{rprintln, rtt_init_print};
use va108xx_hal::{ use va108xx_hal::{
gpio::PinsB, gpio::PinsB,
pac, pac,
prelude::*, prelude::*,
time::Hertz,
uart::{self, IrqCfg, IrqResult, UartWithIrqBase}, uart::{self, IrqCfg, IrqResult, UartWithIrqBase},
}; };
@ -44,19 +43,14 @@ mod app {
pub timeout: bool, pub timeout: bool,
} }
rtic_monotonics::systick_monotonic!(Mono, 1_000);
#[init] #[init]
fn init(cx: init::Context) -> (Shared, Local) { fn init(cx: init::Context) -> (Shared, Local) {
rtt_init_print!(); rtt_init_print!();
//set_print_channel(channels.up.0);
rprintln!("-- VA108xx UART IRQ example application--"); rprintln!("-- VA108xx UART IRQ example application--");
// Initialize the systick interrupt & obtain the token to prove that we did Mono::start(cx.core.SYST, SYSCLK_FREQ.raw());
let systick_mono_token = rtic_monotonics::create_systick_token!();
Systick::start(
cx.core.SYST,
Hertz::from(50.MHz()).raw(),
systick_mono_token,
);
let mut dp = cx.device; let mut dp = cx.device;
let gpiob = PinsB::new(&mut dp.sysconfig, Some(dp.ioconfig), dp.portb); let gpiob = PinsB::new(&mut dp.sysconfig, Some(dp.ioconfig), dp.portb);
@ -74,7 +68,6 @@ mod app {
let (rx_info_tx, rx_info_rx) = make_channel!(RxInfo, 3); let (rx_info_tx, rx_info_rx) = make_channel!(RxInfo, 3);
let rx_buf: [u8; 64] = [0; 64]; let rx_buf: [u8; 64] = [0; 64];
//reply_handler::spawn().expect("spawning reply handler failed");
( (
Shared { irq_uart, rx_buf }, Shared { irq_uart, rx_buf },
Local { Local {
@ -112,8 +105,8 @@ mod app {
.expect("Read operation init failed"); .expect("Read operation init failed");
let mut end_idx = 0; let mut end_idx = 0;
for idx in 0..rx_buf.len() { for (idx, val) in rx_buf.iter().enumerate() {
if (rx_buf[idx] as char) == '\n' { if (*val as char) == '\n' {
end_idx = idx; end_idx = idx;
break; break;
} }

4
examples/rtic/src/lib.rs Normal file
View File

@ -0,0 +1,4 @@
#![no_std]
use va108xx_hal::time::Hertz;
pub const SYSCLK_FREQ: Hertz = Hertz::from_raw(50_000_000);

71
examples/rtic/src/main.rs Normal file
View File

@ -0,0 +1,71 @@
//! RTIC minimal blinky
#![no_main]
#![no_std]
#[rtic::app(device = pac, dispatchers = [OC31, OC30, OC29])]
mod app {
use cortex_m::asm;
use embedded_hal::digital::StatefulOutputPin;
use panic_rtt_target as _;
use rtic_example::SYSCLK_FREQ;
use rtic_monotonics::systick::prelude::*;
use rtic_monotonics::Monotonic;
use rtt_target::{rprintln, rtt_init_print};
use va108xx_hal::{
gpio::{OutputReadablePushPull, Pin, PinsA, PA10, PA6, PA7},
pac,
};
#[local]
struct Local {
led0: Pin<PA10, OutputReadablePushPull>,
led1: Pin<PA7, OutputReadablePushPull>,
led2: Pin<PA6, OutputReadablePushPull>,
}
#[shared]
struct Shared {}
rtic_monotonics::systick_monotonic!(Mono, 1_000);
#[init]
fn init(mut cx: init::Context) -> (Shared, Local) {
rtt_init_print!();
rprintln!("-- Vorago VA108xx RTIC template --");
Mono::start(cx.core.SYST, SYSCLK_FREQ.raw());
let porta = PinsA::new(
&mut cx.device.sysconfig,
Some(cx.device.ioconfig),
cx.device.porta,
);
let led0 = porta.pa10.into_readable_push_pull_output();
let led1 = porta.pa7.into_readable_push_pull_output();
let led2 = porta.pa6.into_readable_push_pull_output();
blinky::spawn().ok();
(Shared {}, Local { led0, led1, led2 })
}
// `shared` cannot be accessed from this context
#[idle]
fn idle(_cx: idle::Context) -> ! {
loop {
asm::nop();
}
}
#[task(
priority = 3,
local=[led0, led1, led2],
)]
async fn blinky(cx: blinky::Context) {
loop {
rprintln!("toggling LEDs");
cx.local.led0.toggle().ok();
cx.local.led1.toggle().ok();
cx.local.led2.toggle().ok();
Mono::delay(1000.millis()).await;
}
}
}

View File

@ -4,30 +4,17 @@ version = "0.1.0"
edition = "2021" edition = "2021"
[dependencies] [dependencies]
panic-halt = "0.2"
cortex-m = {version = "0.7", features = ["critical-section-single-core"]} cortex-m = {version = "0.7", features = ["critical-section-single-core"]}
panic-rtt-target = "0.1"
cortex-m-rt = "0.7" cortex-m-rt = "0.7"
panic-halt = "0.2"
panic-rtt-target = "0.1"
critical-section = "1"
rtt-target = "0.5" rtt-target = "0.5"
rtic-sync = { version = "1.3", features = ["defmt-03"] }
embedded-hal = "1" embedded-hal = "1"
embedded-hal-nb = "1" embedded-hal-nb = "1"
embedded-io = "0.6" embedded-io = "0.6"
cortex-m-semihosting = "0.5.0" cortex-m-semihosting = "0.5.0"
# I'd really like to use those, but it is tricky without probe-rs..
# defmt = "0.3"
# defmt-brtt = { version = "0.1", default-features = false, features = ["rtt"] }
# panic-probe = { version = "0.3", features = ["print-defmt"] }
[dependencies.rtic]
version = "2"
features = ["thumbv6-backend"]
[dependencies.rtic-monotonics]
version = "1"
features = ["cortex-m-systick"]
[dependencies.va108xx-hal] [dependencies.va108xx-hal]
version = "0.7"
path = "../../va108xx-hal" path = "../../va108xx-hal"
features = ["rt", "defmt"] features = ["rt", "defmt"]

View File

@ -48,7 +48,7 @@ fn main() -> ! {
let mut cascade_target_1 = let mut cascade_target_1 =
CountDownTimer::new(&mut dp.sysconfig, 50.MHz(), dp.tim4).auto_deactivate(true); CountDownTimer::new(&mut dp.sysconfig, 50.MHz(), dp.tim4).auto_deactivate(true);
cascade_target_1 cascade_target_1
.cascade_0_source(CascadeSource::TimBase, Some(3)) .cascade_0_source(CascadeSource::Tim(3))
.expect("Configuring cascade source for TIM4 failed"); .expect("Configuring cascade source for TIM4 failed");
let mut csd_cfg = CascadeCtrl { let mut csd_cfg = CascadeCtrl {
enb_start_src_csd0: true, enb_start_src_csd0: true,
@ -75,7 +75,7 @@ fn main() -> ! {
CountDownTimer::new(&mut dp.sysconfig, 50.MHz(), dp.tim5).auto_deactivate(true); CountDownTimer::new(&mut dp.sysconfig, 50.MHz(), dp.tim5).auto_deactivate(true);
// Set TIM4 as cascade source // Set TIM4 as cascade source
cascade_target_2 cascade_target_2
.cascade_1_source(CascadeSource::TimBase, Some(4)) .cascade_1_source(CascadeSource::Tim(4))
.expect("Configuring cascade source for TIM5 failed"); .expect("Configuring cascade source for TIM5 failed");
csd_cfg = CascadeCtrl::default(); csd_cfg = CascadeCtrl::default();

View File

@ -3,8 +3,8 @@
#![no_std] #![no_std]
use core::cell::Cell; use core::cell::Cell;
use cortex_m::interrupt::Mutex;
use cortex_m_rt::entry; use cortex_m_rt::entry;
use critical_section::Mutex;
use panic_rtt_target as _; use panic_rtt_target as _;
use rtt_target::{rprintln, rtt_init_print}; use rtt_target::{rprintln, rtt_init_print};
use va108xx_hal::{ use va108xx_hal::{
@ -83,11 +83,12 @@ fn main() -> ! {
} }
} }
loop { loop {
let current_ms = cortex_m::interrupt::free(|cs| MS_COUNTER.borrow(cs).get()); let current_ms = critical_section::with(|cs| MS_COUNTER.borrow(cs).get());
if current_ms - last_ms >= 1000 { if current_ms - last_ms >= 1000 {
last_ms = current_ms; // To prevent drift.
last_ms += 1000;
rprintln!("MS counter: {}", current_ms); rprintln!("MS counter: {}", current_ms);
let second = cortex_m::interrupt::free(|cs| SEC_COUNTER.borrow(cs).get()); let second = critical_section::with(|cs| SEC_COUNTER.borrow(cs).get());
rprintln!("Second counter: {}", second); rprintln!("Second counter: {}", second);
} }
cortex_m::asm::delay(10000); cortex_m::asm::delay(10000);
@ -110,7 +111,7 @@ fn OC0() {
#[interrupt] #[interrupt]
#[allow(non_snake_case)] #[allow(non_snake_case)]
fn OC1() { fn OC1() {
cortex_m::interrupt::free(|cs| { critical_section::with(|cs| {
let mut sec = SEC_COUNTER.borrow(cs).get(); let mut sec = SEC_COUNTER.borrow(cs).get();
sec += 1; sec += 1;
SEC_COUNTER.borrow(cs).set(sec); SEC_COUNTER.borrow(cs).set(sec);

View File

@ -6,6 +6,11 @@ All notable changes to this project will be documented in this file.
The format is based on [Keep a Changelog](http://keepachangelog.com/) The format is based on [Keep a Changelog](http://keepachangelog.com/)
and this project adheres to [Semantic Versioning](http://semver.org/). and this project adheres to [Semantic Versioning](http://semver.org/).
## [unreleased]
- Improves `CascardSource` handling and general API when chosing cascade sources.
- Replaced `utility::unmask_irq` by `enable_interrupt` and `disable_interrupt` API.
## [v0.7.0] 2024-07-04 ## [v0.7.0] 2024-07-04
- Replace `uarta` and `uartb` `Uart` constructors by `new` constructor - Replace `uarta` and `uartb` `Uart` constructors by `new` constructor

View File

@ -19,7 +19,7 @@ embedded-hal-nb = "1"
embedded-io = "0.6" embedded-io = "0.6"
fugit = "0.3" fugit = "0.3"
typenum = "1" typenum = "1"
defmt = { version = "0.3", optional = true } critical-section = "1"
delegate = "0.12" delegate = "0.12"
[dependencies.va108xx] [dependencies.va108xx]
@ -38,9 +38,14 @@ default-features = false
version = "1.14" version = "1.14"
default-features = false default-features = false
[dependencies.defmt]
version = "0.3"
optional = true
[features] [features]
default = ["rt"] default = ["rt"]
rt = ["va108xx/rt"] rt = ["va108xx/rt"]
defmt = ["dep:defmt", "fugit/defmt"]
[package.metadata.docs.rs] [package.metadata.docs.rs]
all-features = true all-features = true

View File

@ -15,7 +15,6 @@ pub mod time;
pub mod timer; pub mod timer;
pub mod typelevel; pub mod typelevel;
pub mod uart; pub mod uart;
pub mod utility;
#[derive(Debug, Eq, Copy, Clone, PartialEq)] #[derive(Debug, Eq, Copy, Clone, PartialEq)]
pub enum FunSel { pub enum FunSel {
@ -98,3 +97,21 @@ pub fn port_mux(
} }
} }
} }
/// 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);
}

View File

@ -7,6 +7,7 @@
pub use crate::IrqCfg; pub use crate::IrqCfg;
use crate::{ use crate::{
clock::{enable_peripheral_clock, PeripheralClocks}, clock::{enable_peripheral_clock, PeripheralClocks},
enable_interrupt,
gpio::{ gpio::{
AltFunc1, AltFunc2, AltFunc3, DynPinId, Pin, PinId, PA0, PA1, PA10, PA11, PA12, PA13, PA14, AltFunc1, AltFunc2, AltFunc3, DynPinId, Pin, PinId, PA0, PA1, PA10, PA11, PA12, PA13, PA14,
PA15, PA2, PA24, PA25, PA26, PA27, PA28, PA29, PA3, PA30, PA31, PA4, PA5, PA6, PA7, PA8, PA15, PA2, PA24, PA25, PA26, PA27, PA28, PA29, PA3, PA30, PA31, PA4, PA5, PA6, PA7, PA8,
@ -17,10 +18,9 @@ use crate::{
time::Hertz, time::Hertz,
timer, timer,
typelevel::Sealed, typelevel::Sealed,
utility::unmask_irq,
}; };
use core::cell::Cell; use core::cell::Cell;
use cortex_m::interrupt::Mutex; use critical_section::Mutex;
use fugit::RateExtU32; use fugit::RateExtU32;
const IRQ_DST_NONE: u32 = 0xffffffff; const IRQ_DST_NONE: u32 = 0xffffffff;
@ -72,25 +72,46 @@ pub enum CascadeSel {
Csd2 = 2, Csd2 = 2,
} }
#[derive(Debug, PartialEq, Eq)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
pub struct InvalidCascadeSourceId;
/// The numbers are the base numbers for bundles like PORTA, PORTB or TIM /// The numbers are the base numbers for bundles like PORTA, PORTB or TIM
#[derive(Debug, PartialEq, Eq)] #[derive(Debug, PartialEq, Eq)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
#[repr(u8)]
pub enum CascadeSource { pub enum CascadeSource {
PortABase = 0, PortA(u8),
PortBBase = 32, PortB(u8),
TimBase = 64, Tim(u8),
RamSbe = 96, RamSbe = 96,
RamMbe = 97, RamMbe = 97,
RomSbe = 98, RomSbe = 98,
RomMbe = 99, RomMbe = 99,
Txev = 100, Txev = 100,
ClockDividerBase = 120, ClockDivider(u8),
} }
#[derive(Debug, PartialEq, Eq)] impl CascadeSource {
pub enum TimerErrors { fn id(&self) -> Result<u8, InvalidCascadeSourceId> {
Canceled, let port_check = |base: u8, id: u8, len: u8| {
/// Invalid input for Cascade source if id > len - 1 {
InvalidCsdSourceInput, return Err(InvalidCascadeSourceId);
}
Ok(base + id)
};
match self {
CascadeSource::PortA(id) => port_check(0, *id, 32),
CascadeSource::PortB(id) => port_check(32, *id, 32),
CascadeSource::Tim(id) => port_check(64, *id, 24),
CascadeSource::RamSbe => Ok(96),
CascadeSource::RamMbe => Ok(97),
CascadeSource::RomSbe => Ok(98),
CascadeSource::RomMbe => Ok(99),
CascadeSource::Txev => Ok(100),
CascadeSource::ClockDivider(id) => port_check(120, *id, 8),
}
}
} }
//================================================================================================== //==================================================================================================
@ -360,89 +381,26 @@ pub struct CountDownTimer<TIM: ValidTim> {
listening: bool, listening: bool,
} }
fn enable_tim_clk(syscfg: &mut pac::Sysconfig, idx: u8) { #[inline(always)]
pub fn enable_tim_clk(syscfg: &mut pac::Sysconfig, idx: u8) {
syscfg syscfg
.tim_clk_enable() .tim_clk_enable()
.modify(|r, w| unsafe { w.bits(r.bits() | (1 << idx)) }); .modify(|r, w| unsafe { w.bits(r.bits() | (1 << idx)) });
} }
#[inline(always)]
pub fn disable_tim_clk(syscfg: &mut pac::Sysconfig, idx: u8) {
syscfg
.tim_clk_enable()
.modify(|r, w| unsafe { w.bits(r.bits() & !(1 << idx)) });
}
unsafe impl<TIM: ValidTim> TimRegInterface for CountDownTimer<TIM> { unsafe impl<TIM: ValidTim> TimRegInterface for CountDownTimer<TIM> {
fn tim_id(&self) -> u8 { fn tim_id(&self) -> u8 {
TIM::TIM_ID TIM::TIM_ID
} }
} }
macro_rules! csd_sel {
($func_name:ident, $csd_reg:ident) => {
/// Configure the Cascade sources
pub fn $func_name(
&mut self,
src: CascadeSource,
id: Option<u8>,
) -> Result<(), TimerErrors> {
let mut id_num = 0;
if let CascadeSource::PortABase
| CascadeSource::PortBBase
| CascadeSource::ClockDividerBase
| CascadeSource::TimBase = src
{
if id.is_none() {
return Err(TimerErrors::InvalidCsdSourceInput);
}
}
if id.is_some() {
id_num = id.unwrap();
}
match src {
CascadeSource::PortABase => {
if id_num > 55 {
return Err(TimerErrors::InvalidCsdSourceInput);
}
self.tim.reg().$csd_reg().write(|w| unsafe {
w.cassel().bits(CascadeSource::PortABase as u8 + id_num)
});
Ok(())
}
CascadeSource::PortBBase => {
if id_num > 23 {
return Err(TimerErrors::InvalidCsdSourceInput);
}
self.tim.reg().$csd_reg().write(|w| unsafe {
w.cassel().bits(CascadeSource::PortBBase as u8 + id_num)
});
Ok(())
}
CascadeSource::TimBase => {
if id_num > 23 {
return Err(TimerErrors::InvalidCsdSourceInput);
}
self.tim.reg().$csd_reg().write(|w| unsafe {
w.cassel().bits(CascadeSource::TimBase as u8 + id_num)
});
Ok(())
}
CascadeSource::ClockDividerBase => {
if id_num > 7 {
return Err(TimerErrors::InvalidCsdSourceInput);
}
self.tim.reg().cascade0().write(|w| unsafe {
w.cassel()
.bits(CascadeSource::ClockDividerBase as u8 + id_num)
});
Ok(())
}
_ => {
self.tim
.reg()
.$csd_reg()
.write(|w| unsafe { w.cassel().bits(src as u8) });
Ok(())
}
}
}
};
}
impl<TIM: ValidTim> CountDownTimer<TIM> { impl<TIM: ValidTim> CountDownTimer<TIM> {
/// Configures a TIM peripheral as a periodic count down timer /// Configures a TIM peripheral as a periodic count down timer
pub fn new(syscfg: &mut pac::Sysconfig, sys_clk: impl Into<Hertz>, tim: TIM) -> Self { pub fn new(syscfg: &mut pac::Sysconfig, sys_clk: impl Into<Hertz>, tim: TIM) -> Self {
@ -554,18 +512,18 @@ impl<TIM: ValidTim> CountDownTimer<TIM> {
#[inline(always)] #[inline(always)]
pub fn enable(&mut self) { pub fn enable(&mut self) {
self.tim.reg().ctrl().modify(|_, w| w.enable().set_bit());
if let Some(irq_cfg) = self.irq_cfg { if let Some(irq_cfg) = self.irq_cfg {
self.enable_interrupt(); self.enable_interrupt();
if irq_cfg.enable { if irq_cfg.enable {
unmask_irq(irq_cfg.irq); unsafe { enable_interrupt(irq_cfg.irq) };
} }
} }
self.tim.reg().enable().write(|w| unsafe { w.bits(1) });
} }
#[inline(always)] #[inline(always)]
pub fn disable(&mut self) { pub fn disable(&mut self) {
self.tim.reg().ctrl().modify(|_, w| w.enable().clear_bit()); self.tim.reg().enable().write(|w| unsafe { w.bits(0) });
} }
/// Disable the counter, setting both enable and active bit to 0 /// Disable the counter, setting both enable and active bit to 0
@ -619,9 +577,32 @@ impl<TIM: ValidTim> CountDownTimer<TIM> {
}); });
} }
csd_sel!(cascade_0_source, cascade0); pub fn cascade_0_source(&mut self, src: CascadeSource) -> Result<(), InvalidCascadeSourceId> {
csd_sel!(cascade_1_source, cascade1); let id = src.id()?;
csd_sel!(cascade_2_source, cascade2); self.tim
.reg()
.cascade0()
.write(|w| unsafe { w.cassel().bits(id) });
Ok(())
}
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(())
}
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(())
}
pub fn curr_freq(&self) -> Hertz { pub fn curr_freq(&self) -> Hertz {
self.curr_freq self.curr_freq
@ -656,12 +637,13 @@ impl<TIM: ValidTim> CountDownTimer<TIM> {
} }
} }
pub fn cancel(&mut self) -> Result<(), TimerErrors> { /// Returns [false] if the timer was not active, and true otherwise.
pub fn cancel(&mut self) -> bool {
if !self.tim.reg().ctrl().read().enable().bit_is_set() { if !self.tim.reg().ctrl().read().enable().bit_is_set() {
return Err(TimerErrors::Canceled); return false;
} }
self.tim.reg().ctrl().write(|w| w.enable().clear_bit()); self.tim.reg().ctrl().write(|w| w.enable().clear_bit());
Ok(()) true
} }
} }
@ -747,7 +729,7 @@ pub fn set_up_ms_delay_provider<TIM: ValidTim>(
/// This function can be called in a specified interrupt handler to increment /// This function can be called in a specified interrupt handler to increment
/// the MS counter /// the MS counter
pub fn default_ms_irq_handler() { pub fn default_ms_irq_handler() {
cortex_m::interrupt::free(|cs| { critical_section::with(|cs| {
let mut ms = MS_COUNTER.borrow(cs).get(); let mut ms = MS_COUNTER.borrow(cs).get();
ms += 1; ms += 1;
MS_COUNTER.borrow(cs).set(ms); MS_COUNTER.borrow(cs).set(ms);
@ -756,7 +738,7 @@ pub fn default_ms_irq_handler() {
/// Get the current MS tick count /// Get the current MS tick count
pub fn get_ms_ticks() -> u32 { pub fn get_ms_ticks() -> u32 {
cortex_m::interrupt::free(|cs| MS_COUNTER.borrow(cs).get()) critical_section::with(|cs| MS_COUNTER.borrow(cs).get())
} }
//================================================================================================== //==================================================================================================

View File

@ -3,7 +3,7 @@
//! ## Examples //! ## Examples
//! //!
//! - [UART simple example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples/simple/examples/uart.rs) //! - [UART simple example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples/simple/examples/uart.rs)
//! - [UART with IRQ and RTIC](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples/simple/examples/uart-irq-rtic.rs) //! - [UART with IRQ and RTIC](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/examples/rtic/bin/uart-rtic.rs)
use core::{marker::PhantomData, ops::Deref}; use core::{marker::PhantomData, ops::Deref};
use embedded_hal_nb::serial::Read; use embedded_hal_nb::serial::Read;
use fugit::RateExtU32; use fugit::RateExtU32;
@ -11,13 +11,13 @@ use fugit::RateExtU32;
pub use crate::IrqCfg; pub use crate::IrqCfg;
use crate::{ use crate::{
clock::{enable_peripheral_clock, PeripheralClocks}, clock::{enable_peripheral_clock, PeripheralClocks},
enable_interrupt,
gpio::pin::{ gpio::pin::{
AltFunc1, AltFunc2, AltFunc3, Pin, PA16, PA17, PA18, PA19, PA2, PA26, PA27, PA3, PA30, AltFunc1, AltFunc2, AltFunc3, Pin, PA16, PA17, PA18, PA19, PA2, PA26, PA27, PA3, PA30,
PA31, PA8, PA9, PB18, PB19, PB20, PB21, PB22, PB23, PB6, PB7, PB8, PB9, PA31, PA8, PA9, PB18, PB19, PB20, PB21, PB22, PB23, PB6, PB7, PB8, PB9,
}, },
pac::{self, uarta as uart_base}, pac::{self, uarta as uart_base},
time::Hertz, time::Hertz,
utility::unmask_irq,
PeripheralSelect, PeripheralSelect,
}; };
@ -638,7 +638,7 @@ impl Instance for pac::Uartb {
const PERIPH_SEL: PeripheralSelect = PeripheralSelect::Uart1; const PERIPH_SEL: PeripheralSelect = PeripheralSelect::Uart1;
} }
impl<UART: Instance> UartWithIrqBase<UART> { impl<Uart: Instance> UartWithIrqBase<Uart> {
fn init(self, sys_cfg: Option<&mut pac::Sysconfig>, irq_sel: Option<&mut pac::Irqsel>) -> Self { fn init(self, sys_cfg: Option<&mut pac::Sysconfig>, irq_sel: Option<&mut pac::Irqsel>) -> Self {
if let Some(sys_cfg) = sys_cfg { if let Some(sys_cfg) = sys_cfg {
enable_peripheral_clock(sys_cfg, PeripheralClocks::Irqsel) enable_peripheral_clock(sys_cfg, PeripheralClocks::Irqsel)
@ -646,7 +646,7 @@ impl<UART: Instance> UartWithIrqBase<UART> {
if let Some(irq_sel) = irq_sel { if let Some(irq_sel) = irq_sel {
if self.irq_info.irq_cfg.route { if self.irq_info.irq_cfg.route {
irq_sel irq_sel
.uart0(UART::IDX as usize) .uart0(Uart::IDX as usize)
.write(|w| unsafe { w.bits(self.irq_info.irq_cfg.irq as u32) }); .write(|w| unsafe { w.bits(self.irq_info.irq_cfg.irq as u32) });
} }
} }
@ -676,7 +676,9 @@ impl<UART: Instance> UartWithIrqBase<UART> {
self.uart.enable_tx(); self.uart.enable_tx();
self.enable_rx_irq_sources(enb_timeout_irq); self.enable_rx_irq_sources(enb_timeout_irq);
if self.irq_info.irq_cfg.enable { if self.irq_info.irq_cfg.enable {
unmask_irq(self.irq_info.irq_cfg.irq); unsafe {
enable_interrupt(self.irq_info.irq_cfg.irq);
}
} }
Ok(()) Ok(())
} }
@ -839,7 +841,7 @@ impl<UART: Instance> UartWithIrqBase<UART> {
self.irq_info.rx_len = 0; self.irq_info.rx_len = 0;
} }
pub fn release(self) -> UART { pub fn release(self) -> Uart {
self.uart.release() self.uart.release()
} }
} }

View File

@ -1,16 +0,0 @@
//! # API for utility functions like the Error Detection and Correction (EDAC) block
//!
//! Some more information about the recommended scrub rates can be found on the
//! [Vorago White Paper website](https://www.voragotech.com/resources) in the
//! application note AN1212
use crate::pac;
/// Unmask and enable an IRQ with the given interrupt number
///
/// ## Safety
///
/// The unmask function can break mask-based critical sections
#[inline]
pub(crate) fn unmask_irq(irq: pac::Interrupt) {
unsafe { cortex_m::peripheral::NVIC::unmask(irq) };
}

View File

@ -4,7 +4,7 @@
//! //!
//! ## Examples //! ## Examples
//! //!
//! - [Temperature Sensor example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/vorago-reb1/examples/adt75-temp-sensor.rs //! - [Temperature Sensor example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/vorago-reb1/examples/adt75-temp-sensor.rs)
use embedded_hal::i2c::{I2c, SevenBitAddress}; use embedded_hal::i2c::{I2c, SevenBitAddress};
use va108xx_hal::{ use va108xx_hal::{
i2c::{Error, I2cMaster, I2cSpeed, InitError, MasterConfig}, i2c::{Error, I2cMaster, I2cSpeed, InitError, MasterConfig},

View File

@ -20,7 +20,7 @@
"runToEntryPoint": "main", "runToEntryPoint": "main",
"rttConfig": { "rttConfig": {
"enabled": true, "enabled": true,
"address": "0x10000000", "address": "auto",
"decoders": [ "decoders": [
{ {
"port": 0, "port": 0,
@ -44,7 +44,7 @@
"runToEntryPoint": "main", "runToEntryPoint": "main",
"rttConfig": { "rttConfig": {
"enabled": true, "enabled": true,
"address": "0x10000000", "address": "auto",
"decoders": [ "decoders": [
{ {
"port": 0, "port": 0,
@ -68,7 +68,7 @@
"runToEntryPoint": "main", "runToEntryPoint": "main",
"rttConfig": { "rttConfig": {
"enabled": true, "enabled": true,
"address": "0x10000000", "address": "auto",
"decoders": [ "decoders": [
{ {
"port": 0, "port": 0,
@ -92,7 +92,7 @@
"runToEntryPoint": "main", "runToEntryPoint": "main",
"rttConfig": { "rttConfig": {
"enabled": true, "enabled": true,
"address": "0x10000000", "address": "auto",
"decoders": [ "decoders": [
{ {
"port": 0, "port": 0,
@ -116,7 +116,7 @@
"runToEntryPoint": "main", "runToEntryPoint": "main",
"rttConfig": { "rttConfig": {
"enabled": true, "enabled": true,
"address": "0x10000000", "address": "auto",
"decoders": [ "decoders": [
{ {
"port": 0, "port": 0,
@ -129,7 +129,7 @@
{ {
"type": "cortex-debug", "type": "cortex-debug",
"request": "launch", "request": "launch",
"name": "Debug UART", "name": "UART Example",
"servertype": "jlink", "servertype": "jlink",
"cwd": "${workspaceRoot}", "cwd": "${workspaceRoot}",
"device": "Cortex-M0", "device": "Cortex-M0",
@ -140,7 +140,7 @@
"runToEntryPoint": "main", "runToEntryPoint": "main",
"rttConfig": { "rttConfig": {
"enabled": true, "enabled": true,
"address": "0x10000000", "address": "auto",
"decoders": [ "decoders": [
{ {
"port": 0, "port": 0,
@ -164,7 +164,7 @@
"runToEntryPoint": "main", "runToEntryPoint": "main",
"rttConfig": { "rttConfig": {
"enabled": true, "enabled": true,
"address": "0x10000000", "address": "auto",
"decoders": [ "decoders": [
{ {
"port": 0, "port": 0,
@ -188,7 +188,7 @@
"runToEntryPoint": "main", "runToEntryPoint": "main",
"rttConfig": { "rttConfig": {
"enabled": true, "enabled": true,
"address": "0x10000000", "address": "auto",
"decoders": [ "decoders": [
{ {
"port": 0, "port": 0,
@ -212,7 +212,7 @@
"runToEntryPoint": "main", "runToEntryPoint": "main",
"rttConfig": { "rttConfig": {
"enabled": true, "enabled": true,
"address": "0x10000000", "address": "auto",
"decoders": [ "decoders": [
{ {
"port": 0, "port": 0,
@ -236,7 +236,7 @@
"runToEntryPoint": "main", "runToEntryPoint": "main",
"rttConfig": { "rttConfig": {
"enabled": true, "enabled": true,
"address": "0x10000000", "address": "auto",
"decoders": [ "decoders": [
{ {
"port": 0, "port": 0,
@ -284,7 +284,7 @@
"runToEntryPoint": "main", "runToEntryPoint": "main",
"rttConfig": { "rttConfig": {
"enabled": true, "enabled": true,
"address": "0x10000000", "address": "auto",
"decoders": [ "decoders": [
{ {
"port": 0, "port": 0,
@ -321,7 +321,7 @@
"runToEntryPoint": "main", "runToEntryPoint": "main",
"rttConfig": { "rttConfig": {
"enabled": true, "enabled": true,
"address": "0x10000000", "address": "auto",
"decoders": [ "decoders": [
{ {
"port": 0, "port": 0,
@ -340,12 +340,60 @@
"device": "Cortex-M0", "device": "Cortex-M0",
"svdFile": "./va108xx/svd/va108xx.svd.patched", "svdFile": "./va108xx/svd/va108xx.svd.patched",
"preLaunchTask": "rust: cargo build uart irq", "preLaunchTask": "rust: cargo build uart irq",
"executable": "${workspaceFolder}/target/thumbv6m-none-eabi/debug/examples/uart-irq-rtic", "executable": "${workspaceFolder}/target/thumbv6m-none-eabi/debug/uart-rtic",
"interface": "jtag", "interface": "jtag",
"runToEntryPoint": "main", "runToEntryPoint": "main",
"rttConfig": { "rttConfig": {
"enabled": true, "enabled": true,
"address": "0x10000000", "address": "auto",
"decoders": [
{
"port": 0,
"timestamp": true,
"type": "console"
}
]
}
},
{
"type": "cortex-debug",
"request": "launch",
"name": "RTIC Example",
"servertype": "jlink",
"cwd": "${workspaceRoot}",
"device": "Cortex-M0",
"svdFile": "./va108xx/svd/va108xx.svd.patched",
"preLaunchTask": "rtic-example",
"executable": "${workspaceFolder}/target/thumbv6m-none-eabi/debug/rtic-example",
"interface": "jtag",
"runToEntryPoint": "main",
"rttConfig": {
"enabled": true,
"address": "auto",
"decoders": [
{
"port": 0,
"timestamp": true,
"type": "console"
}
]
}
},
{
"type": "cortex-debug",
"request": "launch",
"name": "Embassy Example",
"servertype": "jlink",
"cwd": "${workspaceRoot}",
"device": "Cortex-M0",
"svdFile": "./va108xx/svd/va108xx.svd.patched",
"preLaunchTask": "embassy-example",
"executable": "${workspaceFolder}/target/thumbv6m-none-eabi/debug/embassy-example",
"interface": "jtag",
"runToEntryPoint": "main",
"rttConfig": {
"enabled": true,
"address": "auto",
"decoders": [ "decoders": [
{ {
"port": 0, "port": 0,

View File

@ -67,8 +67,6 @@
"command": "~/.cargo/bin/cargo", // note: full path to the cargo "command": "~/.cargo/bin/cargo", // note: full path to the cargo
"args": [ "args": [
"build", "build",
"-p",
"va108xx-hal",
"--example", "--example",
"uart", "uart",
], ],
@ -129,10 +127,8 @@
"command": "~/.cargo/bin/cargo", // note: full path to the cargo "command": "~/.cargo/bin/cargo", // note: full path to the cargo
"args": [ "args": [
"build", "build",
"--example", "--bin",
"uart-irq-rtic", "uart-rtic",
"--features",
"rt"
], ],
"group": { "group": {
"kind": "build", "kind": "build",
@ -248,5 +244,25 @@
"isDefault": true "isDefault": true
} }
}, },
{
"label": "rtic-example",
"type": "shell",
"command": "~/.cargo/bin/cargo", // note: full path to the cargo
"args": [
"build",
"--bin",
"rtic-example",
],
},
{
"label": "embassy-example",
"type": "shell",
"command": "~/.cargo/bin/cargo", // note: full path to the cargo
"args": [
"build",
"--bin",
"embassy-example",
],
},
] ]
} }