New VA108xx Rust workspace structure + dependency updates
- The workspace is now a monorepo without submodules. The HAL, PAC and BSP are integrated directly - Update all dependencies: embedded-hal v1 and RTIC v2
This commit is contained in:
25
vorago-reb1/examples/adt75-temp-sensor.rs
Normal file
25
vorago-reb1/examples/adt75-temp-sensor.rs
Normal file
@ -0,0 +1,25 @@
|
||||
#![no_main]
|
||||
#![no_std]
|
||||
use cortex_m_rt::entry;
|
||||
use embedded_hal::delay::DelayNs;
|
||||
use panic_rtt_target as _;
|
||||
use rtt_target::{rprintln, rtt_init_print};
|
||||
use va108xx_hal::{pac, prelude::*, timer::set_up_ms_delay_provider};
|
||||
use vorago_reb1::temp_sensor::Adt75TempSensor;
|
||||
|
||||
#[entry]
|
||||
fn main() -> ! {
|
||||
rtt_init_print!();
|
||||
rprintln!("-- Vorago Temperature Sensor and I2C Example --");
|
||||
let mut dp = pac::Peripherals::take().unwrap();
|
||||
let mut delay = set_up_ms_delay_provider(&mut dp.sysconfig, 50.MHz(), dp.tim0);
|
||||
let mut temp_sensor = Adt75TempSensor::new(dp.i2ca, 50.MHz(), Some(&mut dp.sysconfig))
|
||||
.expect("Creating temperature sensor struct failed");
|
||||
loop {
|
||||
let temp = temp_sensor
|
||||
.read_temperature()
|
||||
.expect("Failed reading temperature");
|
||||
rprintln!("Temperature in Celcius: {}", temp);
|
||||
delay.delay_ms(500);
|
||||
}
|
||||
}
|
78
vorago-reb1/examples/adxl343-accelerometer.rs
Normal file
78
vorago-reb1/examples/adxl343-accelerometer.rs
Normal file
@ -0,0 +1,78 @@
|
||||
//! ADXL343 accelerometer example
|
||||
//!
|
||||
//! Please note that the default REB1 board is not populated with the ADXL343BCCZ-RL7.
|
||||
//! To use this example, this chip needs to be soldered onto the board.
|
||||
#![no_main]
|
||||
#![no_std]
|
||||
use cortex_m_rt::entry;
|
||||
use embedded_hal::spi::SpiBus;
|
||||
use embedded_hal::{delay::DelayNs, digital::OutputPin};
|
||||
use panic_rtt_target as _;
|
||||
use rtt_target::{rprintln, rtt_init_print};
|
||||
use va108xx_hal::{
|
||||
gpio::PinsA,
|
||||
pac,
|
||||
prelude::*,
|
||||
spi::{Spi, SpiConfig, TransferConfig},
|
||||
timer::set_up_ms_delay_provider,
|
||||
};
|
||||
|
||||
const READ_MASK: u8 = 1 << 7;
|
||||
const _MULTI_BYTE_MASK: u8 = 1 << 6;
|
||||
const DEVID_REG: u8 = 0x00;
|
||||
|
||||
const POWER_CTL_REG: u8 = 0x2D;
|
||||
const PWR_MEASUREMENT_MODE_MASK: u8 = 1 << 3;
|
||||
|
||||
#[entry]
|
||||
fn main() -> ! {
|
||||
rtt_init_print!();
|
||||
rprintln!("-- Vorago Accelerometer Example --");
|
||||
let mut dp = pac::Peripherals::take().unwrap();
|
||||
let mut delay = set_up_ms_delay_provider(&mut dp.sysconfig, 50.MHz(), dp.tim0);
|
||||
let pinsa = PinsA::new(&mut dp.sysconfig, None, dp.porta);
|
||||
let spi_cfg = SpiConfig::default();
|
||||
let (sck, mosi, miso) = (
|
||||
pinsa.pa20.into_funsel_2(),
|
||||
pinsa.pa19.into_funsel_2(),
|
||||
pinsa.pa18.into_funsel_2(),
|
||||
);
|
||||
let cs_pin = pinsa.pa16.into_funsel_2();
|
||||
|
||||
// Need to set the ADC chip select low
|
||||
let mut adc_cs = pinsa.pa17.into_push_pull_output();
|
||||
adc_cs
|
||||
.set_high()
|
||||
.expect("Setting ADC chip select high failed");
|
||||
|
||||
let transfer_cfg = TransferConfig::new(
|
||||
1.MHz(),
|
||||
embedded_hal::spi::MODE_3,
|
||||
Some(cs_pin),
|
||||
false,
|
||||
true,
|
||||
);
|
||||
let mut spi = Spi::spib(
|
||||
dp.spib,
|
||||
(sck, miso, mosi),
|
||||
50.MHz(),
|
||||
spi_cfg,
|
||||
Some(&mut dp.sysconfig),
|
||||
Some(&transfer_cfg.downgrade()),
|
||||
);
|
||||
|
||||
let mut tx_rx_buf: [u8; 3] = [0; 3];
|
||||
tx_rx_buf[0] = READ_MASK | DEVID_REG;
|
||||
spi.transfer_in_place(&mut tx_rx_buf[0..2])
|
||||
.expect("Reading DEVID register failed");
|
||||
rprintln!("DEVID register: {}", tx_rx_buf[1]);
|
||||
|
||||
tx_rx_buf[0] = POWER_CTL_REG;
|
||||
tx_rx_buf[1] = PWR_MEASUREMENT_MODE_MASK;
|
||||
spi.write(&tx_rx_buf[0..2])
|
||||
.expect("Enabling measurement mode failed");
|
||||
|
||||
loop {
|
||||
delay.delay_ms(500);
|
||||
}
|
||||
}
|
106
vorago-reb1/examples/blinky-button-irq.rs
Normal file
106
vorago-reb1/examples/blinky-button-irq.rs
Normal file
@ -0,0 +1,106 @@
|
||||
//! Blinky button application for the REB1 board
|
||||
#![no_main]
|
||||
#![no_std]
|
||||
|
||||
use core::cell::RefCell;
|
||||
|
||||
use cortex_m::interrupt::Mutex;
|
||||
use cortex_m_rt::entry;
|
||||
use panic_rtt_target as _;
|
||||
use rtt_target::{rprintln, rtt_init_print};
|
||||
use va108xx_hal::{
|
||||
clock::{set_clk_div_register, FilterClkSel},
|
||||
gpio::{FilterType, InterruptEdge, PinsA},
|
||||
pac::{self, interrupt},
|
||||
prelude::*,
|
||||
timer::{default_ms_irq_handler, set_up_ms_tick, IrqCfg},
|
||||
};
|
||||
use vorago_reb1::button::Button;
|
||||
use vorago_reb1::leds::Leds;
|
||||
|
||||
static LEDS: Mutex<RefCell<Option<Leds>>> = Mutex::new(RefCell::new(None));
|
||||
static BUTTON: Mutex<RefCell<Option<Button>>> = Mutex::new(RefCell::new(None));
|
||||
|
||||
#[derive(Debug, PartialEq)]
|
||||
pub enum PressMode {
|
||||
Toggle,
|
||||
Keep,
|
||||
}
|
||||
|
||||
// You can change the press mode here
|
||||
const PRESS_MODE: PressMode = PressMode::Keep;
|
||||
|
||||
#[entry]
|
||||
fn main() -> ! {
|
||||
rtt_init_print!();
|
||||
rprintln!("-- Vorago Button IRQ Example --");
|
||||
let mut dp = pac::Peripherals::take().unwrap();
|
||||
let pinsa = PinsA::new(&mut dp.sysconfig, Some(dp.ioconfig), dp.porta);
|
||||
let edge_irq = match PRESS_MODE {
|
||||
PressMode::Toggle => InterruptEdge::HighToLow,
|
||||
PressMode::Keep => InterruptEdge::BothEdges,
|
||||
};
|
||||
|
||||
// Configure an edge interrupt on the button and route it to interrupt vector 15
|
||||
let mut button = Button::new(pinsa.pa11.into_floating_input()).edge_irq(
|
||||
edge_irq,
|
||||
IrqCfg::new(pac::interrupt::OC15, true, true),
|
||||
Some(&mut dp.sysconfig),
|
||||
Some(&mut dp.irqsel),
|
||||
);
|
||||
|
||||
if PRESS_MODE == PressMode::Toggle {
|
||||
// This filter debounces the switch for edge based interrupts
|
||||
button = button.filter_type(FilterType::FilterFourClockCycles, FilterClkSel::Clk1);
|
||||
set_clk_div_register(&mut dp.sysconfig, FilterClkSel::Clk1, 50_000);
|
||||
}
|
||||
|
||||
set_up_ms_tick(
|
||||
IrqCfg::new(pac::Interrupt::OC0, true, true),
|
||||
&mut dp.sysconfig,
|
||||
Some(&mut dp.irqsel),
|
||||
50.MHz(),
|
||||
dp.tim0,
|
||||
);
|
||||
let mut leds = Leds::new(
|
||||
pinsa.pa10.into_push_pull_output(),
|
||||
pinsa.pa7.into_push_pull_output(),
|
||||
pinsa.pa6.into_push_pull_output(),
|
||||
);
|
||||
for led in leds.iter_mut() {
|
||||
led.off();
|
||||
}
|
||||
// Make both button and LEDs accessible from the IRQ handler as well
|
||||
cortex_m::interrupt::free(|cs| {
|
||||
LEDS.borrow(cs).replace(Some(leds));
|
||||
BUTTON.borrow(cs).replace(Some(button));
|
||||
});
|
||||
loop {
|
||||
cortex_m::asm::nop();
|
||||
}
|
||||
}
|
||||
|
||||
#[interrupt]
|
||||
fn OC0() {
|
||||
default_ms_irq_handler();
|
||||
}
|
||||
|
||||
#[interrupt]
|
||||
fn OC15() {
|
||||
cortex_m::interrupt::free(|cs| {
|
||||
if PRESS_MODE == PressMode::Toggle {
|
||||
if let Some(ref mut leds) = LEDS.borrow(cs).borrow_mut().as_deref_mut() {
|
||||
leds[0].toggle();
|
||||
}
|
||||
} else if let (Some(ref mut leds), Some(ref mut button)) = (
|
||||
LEDS.borrow(cs).borrow_mut().as_deref_mut(),
|
||||
BUTTON.borrow(cs).borrow_mut().as_mut(),
|
||||
) {
|
||||
if button.released() {
|
||||
leds[0].off();
|
||||
} else {
|
||||
leds[0].on();
|
||||
}
|
||||
}
|
||||
});
|
||||
}
|
144
vorago-reb1/examples/blinky-button-rtic.rs
Normal file
144
vorago-reb1/examples/blinky-button-rtic.rs
Normal file
@ -0,0 +1,144 @@
|
||||
//! Blinky button application for the REB1 board using RTIC
|
||||
#![no_main]
|
||||
#![no_std]
|
||||
|
||||
#[rtic::app(device = pac)]
|
||||
mod app {
|
||||
use panic_rtt_target as _;
|
||||
use rtt_target::{rprintln, rtt_init_default, set_print_channel};
|
||||
use va108xx_hal::{
|
||||
clock::{set_clk_div_register, FilterClkSel},
|
||||
gpio::{FilterType, InterruptEdge, PinsA},
|
||||
pac,
|
||||
prelude::*,
|
||||
timer::{default_ms_irq_handler, set_up_ms_tick, IrqCfg},
|
||||
};
|
||||
use vorago_reb1::button::Button;
|
||||
use vorago_reb1::leds::Leds;
|
||||
|
||||
#[derive(Debug, PartialEq)]
|
||||
pub enum PressMode {
|
||||
Toggle,
|
||||
Keep,
|
||||
}
|
||||
|
||||
#[derive(Debug, PartialEq)]
|
||||
pub enum CfgMode {
|
||||
Prompt,
|
||||
Fixed,
|
||||
}
|
||||
|
||||
const CFG_MODE: CfgMode = CfgMode::Fixed;
|
||||
// You can change the press mode here
|
||||
const DEFAULT_MODE: PressMode = PressMode::Toggle;
|
||||
|
||||
#[local]
|
||||
struct Local {
|
||||
leds: Leds,
|
||||
button: Button,
|
||||
mode: PressMode,
|
||||
}
|
||||
|
||||
#[shared]
|
||||
struct Shared {}
|
||||
|
||||
#[init]
|
||||
fn init(ctx: init::Context) -> (Shared, Local, init::Monotonics) {
|
||||
let channels = rtt_init_default!();
|
||||
set_print_channel(channels.up.0);
|
||||
rprintln!("-- Vorago Button IRQ Example --");
|
||||
let mode = match CFG_MODE {
|
||||
// Ask mode from user via RTT
|
||||
CfgMode::Prompt => prompt_mode(channels.down.0),
|
||||
// Use mode hardcoded in `DEFAULT_MODE`
|
||||
CfgMode::Fixed => DEFAULT_MODE,
|
||||
};
|
||||
rprintln!("Using {:?} mode", mode);
|
||||
|
||||
let mut dp = ctx.device;
|
||||
let pinsa = PinsA::new(&mut dp.sysconfig, Some(dp.ioconfig), dp.porta);
|
||||
let edge_irq = match mode {
|
||||
PressMode::Toggle => InterruptEdge::HighToLow,
|
||||
PressMode::Keep => InterruptEdge::BothEdges,
|
||||
};
|
||||
|
||||
// Configure an edge interrupt on the button and route it to interrupt vector 15
|
||||
let mut button = Button::new(pinsa.pa11.into_floating_input()).edge_irq(
|
||||
edge_irq,
|
||||
IrqCfg::new(pac::interrupt::OC15, true, true),
|
||||
Some(&mut dp.sysconfig),
|
||||
Some(&mut dp.irqsel),
|
||||
);
|
||||
|
||||
if mode == PressMode::Toggle {
|
||||
// This filter debounces the switch for edge based interrupts
|
||||
button = button.filter_type(FilterType::FilterFourClockCycles, FilterClkSel::Clk1);
|
||||
set_clk_div_register(&mut dp.sysconfig, FilterClkSel::Clk1, 50_000);
|
||||
}
|
||||
let mut leds = Leds::new(
|
||||
pinsa.pa10.into_push_pull_output(),
|
||||
pinsa.pa7.into_push_pull_output(),
|
||||
pinsa.pa6.into_push_pull_output(),
|
||||
);
|
||||
for led in leds.iter_mut() {
|
||||
led.off();
|
||||
}
|
||||
set_up_ms_tick(
|
||||
IrqCfg::new(pac::Interrupt::OC0, true, true),
|
||||
&mut dp.sysconfig,
|
||||
Some(&mut dp.irqsel),
|
||||
50.MHz(),
|
||||
dp.tim0,
|
||||
);
|
||||
(Shared {}, Local { leds, button, mode }, init::Monotonics())
|
||||
}
|
||||
|
||||
// `shared` cannot be accessed from this context
|
||||
#[idle]
|
||||
fn idle(_cx: idle::Context) -> ! {
|
||||
loop {
|
||||
cortex_m::asm::nop();
|
||||
}
|
||||
}
|
||||
|
||||
#[task(binds = OC15, local=[button, leds, mode])]
|
||||
fn button_task(cx: button_task::Context) {
|
||||
let leds = cx.local.leds;
|
||||
let button = cx.local.button;
|
||||
let mode = cx.local.mode;
|
||||
if *mode == PressMode::Toggle {
|
||||
leds[0].toggle();
|
||||
} else {
|
||||
if button.released() {
|
||||
leds[0].off();
|
||||
} else {
|
||||
leds[0].on();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[task(binds = OC0)]
|
||||
fn ms_tick(_cx: ms_tick::Context) {
|
||||
default_ms_irq_handler();
|
||||
}
|
||||
|
||||
fn prompt_mode(mut down_channel: rtt_target::DownChannel) -> PressMode {
|
||||
rprintln!("Using prompt mode");
|
||||
rprintln!("Please enter the mode [0: Toggle, 1: Keep]");
|
||||
let mut read_buf: [u8; 16] = [0; 16];
|
||||
let mut read;
|
||||
loop {
|
||||
read = down_channel.read(&mut read_buf);
|
||||
for i in 0..read {
|
||||
let val = read_buf[i] as char;
|
||||
if val == '0' || val == '1' {
|
||||
return if val == '0' {
|
||||
PressMode::Toggle
|
||||
} else {
|
||||
PressMode::Keep
|
||||
};
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
115
vorago-reb1/examples/blinky-leds.rs
Normal file
115
vorago-reb1/examples/blinky-leds.rs
Normal file
@ -0,0 +1,115 @@
|
||||
//! Blinky examples using the PAC directly, the HAL, or the BSP
|
||||
//!
|
||||
//! Additional note on LEDs:
|
||||
//! Be not afraid: Pulling the GPIOs low makes the LEDs blink. See REB1
|
||||
//! schematic for more details.
|
||||
#![no_main]
|
||||
#![no_std]
|
||||
|
||||
use cortex_m_rt::entry;
|
||||
use embedded_hal::delay::DelayNs;
|
||||
use embedded_hal::digital::{OutputPin, StatefulOutputPin};
|
||||
use panic_halt as _;
|
||||
use va108xx_hal::{gpio::pins::PinsA, pac, prelude::*, timer::set_up_ms_delay_provider};
|
||||
use vorago_reb1::leds::Leds;
|
||||
|
||||
// REB LED pin definitions. All on port A
|
||||
const LED_D2: u32 = 1 << 10;
|
||||
const LED_D3: u32 = 1 << 7;
|
||||
const LED_D4: u32 = 1 << 6;
|
||||
|
||||
#[allow(dead_code)]
|
||||
enum LibType {
|
||||
Pac,
|
||||
Hal,
|
||||
Bsp,
|
||||
}
|
||||
|
||||
#[entry]
|
||||
fn main() -> ! {
|
||||
let mut dp = pac::Peripherals::take().unwrap();
|
||||
|
||||
let lib_type = LibType::Bsp;
|
||||
|
||||
match lib_type {
|
||||
LibType::Pac => {
|
||||
// Enable all peripheral clocks
|
||||
dp.sysconfig
|
||||
.peripheral_clk_enable()
|
||||
.modify(|_, w| unsafe { w.bits(0xffffffff) });
|
||||
dp.porta
|
||||
.dir()
|
||||
.modify(|_, w| unsafe { w.bits(LED_D2 | LED_D3 | LED_D4) });
|
||||
dp.porta
|
||||
.datamask()
|
||||
.modify(|_, w| unsafe { w.bits(LED_D2 | LED_D3 | LED_D4) });
|
||||
for _ in 0..10 {
|
||||
dp.porta
|
||||
.clrout()
|
||||
.write(|w| unsafe { w.bits(LED_D2 | LED_D3 | LED_D4) });
|
||||
cortex_m::asm::delay(5_000_000);
|
||||
dp.porta
|
||||
.setout()
|
||||
.write(|w| unsafe { w.bits(LED_D2 | LED_D3 | LED_D4) });
|
||||
cortex_m::asm::delay(5_000_000);
|
||||
}
|
||||
loop {
|
||||
dp.porta
|
||||
.togout()
|
||||
.write(|w| unsafe { w.bits(LED_D2 | LED_D3 | LED_D4) });
|
||||
cortex_m::asm::delay(25_000_000);
|
||||
}
|
||||
}
|
||||
LibType::Hal => {
|
||||
let pins = PinsA::new(&mut dp.sysconfig, Some(dp.ioconfig), dp.porta);
|
||||
let mut led1 = pins.pa10.into_readable_push_pull_output();
|
||||
let mut led2 = pins.pa7.into_readable_push_pull_output();
|
||||
let mut led3 = pins.pa6.into_readable_push_pull_output();
|
||||
let mut delay = set_up_ms_delay_provider(&mut dp.sysconfig, 50.MHz(), dp.tim0);
|
||||
for _ in 0..10 {
|
||||
led1.set_low().ok();
|
||||
led2.set_low().ok();
|
||||
led3.set_low().ok();
|
||||
delay.delay_ms(200);
|
||||
led1.set_high().ok();
|
||||
led2.set_high().ok();
|
||||
led3.set_high().ok();
|
||||
delay.delay_ms(200);
|
||||
}
|
||||
loop {
|
||||
led1.toggle().ok();
|
||||
delay.delay_ms(200);
|
||||
led2.toggle().ok();
|
||||
delay.delay_ms(200);
|
||||
// Alternatively use deidscted register.
|
||||
led3.toggle_with_toggle_reg();
|
||||
delay.delay_ms(200);
|
||||
}
|
||||
}
|
||||
LibType::Bsp => {
|
||||
let pinsa = PinsA::new(&mut dp.sysconfig, Some(dp.ioconfig), dp.porta);
|
||||
let mut leds = Leds::new(
|
||||
pinsa.pa10.into_push_pull_output(),
|
||||
pinsa.pa7.into_push_pull_output(),
|
||||
pinsa.pa6.into_push_pull_output(),
|
||||
);
|
||||
let mut delay = set_up_ms_delay_provider(&mut dp.sysconfig, 50.MHz(), dp.tim0);
|
||||
loop {
|
||||
for _ in 0..10 {
|
||||
// Blink all LEDs quickly
|
||||
for led in leds.iter_mut() {
|
||||
led.toggle();
|
||||
}
|
||||
delay.delay_ms(500);
|
||||
}
|
||||
// Now use a wave pattern
|
||||
loop {
|
||||
for led in leds.iter_mut() {
|
||||
led.toggle();
|
||||
delay.delay_ms(200);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
345
vorago-reb1/examples/max11619-adc.rs
Normal file
345
vorago-reb1/examples/max11619-adc.rs
Normal file
@ -0,0 +1,345 @@
|
||||
//! MAX11619 ADC example applikcation
|
||||
#![no_main]
|
||||
#![no_std]
|
||||
|
||||
use core::convert::Infallible;
|
||||
|
||||
use cortex_m_rt::entry;
|
||||
use embedded_hal::digital::OutputPin;
|
||||
use embedded_hal::spi::{SpiBus, SpiDevice};
|
||||
use embedded_hal::{delay::DelayNs, spi};
|
||||
use max116xx_10bit::VoltageRefMode;
|
||||
use max116xx_10bit::{AveragingConversions, AveragingResults};
|
||||
use panic_rtt_target as _;
|
||||
use rtt_target::{rprintln, rtt_init_print};
|
||||
use va108xx_hal::spi::{NoneT, OptionalHwCs};
|
||||
use va108xx_hal::timer::CountDownTimer;
|
||||
use va108xx_hal::{
|
||||
gpio::PinsA,
|
||||
pac::{self, interrupt},
|
||||
prelude::*,
|
||||
spi::{Spi, SpiBase, SpiConfig, TransferConfig},
|
||||
timer::{default_ms_irq_handler, set_up_ms_tick, DelayMs, IrqCfg},
|
||||
};
|
||||
use va108xx_hal::{port_mux, FunSel, PortSel};
|
||||
use vorago_reb1::max11619::{
|
||||
max11619_externally_clocked_no_wakeup, max11619_externally_clocked_with_wakeup,
|
||||
max11619_internally_clocked, EocPin, AN2_CHANNEL, POTENTIOMETER_CHANNEL,
|
||||
};
|
||||
|
||||
#[derive(Debug, PartialEq, Copy, Clone)]
|
||||
pub enum ExampleMode {
|
||||
UsingEoc,
|
||||
NotUsingEoc,
|
||||
NotUsingEocWithDelay,
|
||||
}
|
||||
|
||||
#[derive(Debug, PartialEq, Copy, Clone)]
|
||||
pub enum ReadMode {
|
||||
Single,
|
||||
Multiple,
|
||||
MultipleNToHighest,
|
||||
AverageN,
|
||||
}
|
||||
|
||||
#[derive(Debug, PartialEq, Copy, Clone)]
|
||||
pub enum MuxMode {
|
||||
None,
|
||||
PortB19to17,
|
||||
}
|
||||
|
||||
const EXAMPLE_MODE: ExampleMode = ExampleMode::NotUsingEoc;
|
||||
const READ_MODE: ReadMode = ReadMode::Multiple;
|
||||
const MUX_MODE: MuxMode = MuxMode::None;
|
||||
|
||||
// This is probably more or less a re-implementation of https://docs.rs/embedded-hal-bus/latest/embedded_hal_bus/spi/struct.ExclusiveDevice.html.
|
||||
// Users should look at the embedded-hal-bus crate for sharing the bus.
|
||||
pub struct SpiWithHwCs<Delay, HwCs> {
|
||||
inner: SpiBase<pac::Spib, u8>,
|
||||
delay_provider: Delay,
|
||||
hw_cs: HwCs,
|
||||
}
|
||||
|
||||
impl<Delay: DelayNs, HwCs: OptionalHwCs<pac::Spib>> SpiWithHwCs<Delay, HwCs> {
|
||||
pub fn new(spi: SpiBase<pac::Spib, u8>, hw_cs: HwCs, delay_provider: Delay) -> Self {
|
||||
Self {
|
||||
inner: spi,
|
||||
hw_cs,
|
||||
delay_provider,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl<Delay, HwCs> embedded_hal::spi::ErrorType for SpiWithHwCs<Delay, HwCs> {
|
||||
type Error = Infallible;
|
||||
}
|
||||
|
||||
impl<Delay: DelayNs, HwCs: OptionalHwCs<pac::Spib>> SpiDevice for SpiWithHwCs<Delay, HwCs> {
|
||||
fn transaction(
|
||||
&mut self,
|
||||
operations: &mut [spi::Operation<'_, u8>],
|
||||
) -> Result<(), Self::Error> {
|
||||
// Only the HW CS is configured here. This is not really necessary, but showcases
|
||||
// that we could scale this multiple SPI devices.
|
||||
self.inner.cfg_hw_cs_with_pin(&self.hw_cs);
|
||||
for operation in operations {
|
||||
match operation {
|
||||
spi::Operation::Read(buf) => self.inner.read(buf).ok().unwrap(),
|
||||
spi::Operation::Write(buf) => self.inner.write(buf).ok().unwrap(),
|
||||
spi::Operation::Transfer(read, write) => {
|
||||
self.inner.transfer(read, write).ok().unwrap()
|
||||
}
|
||||
spi::Operation::TransferInPlace(buf) => {
|
||||
self.inner.transfer_in_place(buf).ok().unwrap()
|
||||
}
|
||||
spi::Operation::DelayNs(delay) => self.delay_provider.delay_ns(*delay),
|
||||
};
|
||||
}
|
||||
self.inner.cfg_hw_cs_disable();
|
||||
Ok(())
|
||||
}
|
||||
}
|
||||
|
||||
#[entry]
|
||||
fn main() -> ! {
|
||||
rtt_init_print!();
|
||||
rprintln!("-- Vorago ADC Example --");
|
||||
|
||||
let mut dp = pac::Peripherals::take().unwrap();
|
||||
let tim0 = set_up_ms_tick(
|
||||
IrqCfg::new(pac::Interrupt::OC0, true, true),
|
||||
&mut dp.sysconfig,
|
||||
Some(&mut dp.irqsel),
|
||||
50.MHz(),
|
||||
dp.tim0,
|
||||
);
|
||||
let delay = DelayMs::new(tim0).unwrap();
|
||||
unsafe {
|
||||
cortex_m::peripheral::NVIC::unmask(pac::Interrupt::OC0);
|
||||
}
|
||||
|
||||
let pinsa = PinsA::new(&mut dp.sysconfig, None, dp.porta);
|
||||
let spi_cfg = SpiConfig::default();
|
||||
let (sck, mosi, miso) = (
|
||||
pinsa.pa20.into_funsel_2(),
|
||||
pinsa.pa19.into_funsel_2(),
|
||||
pinsa.pa18.into_funsel_2(),
|
||||
);
|
||||
|
||||
if MUX_MODE == MuxMode::PortB19to17 {
|
||||
port_mux(&mut dp.ioconfig, PortSel::PortB, 19, FunSel::Sel1).ok();
|
||||
port_mux(&mut dp.ioconfig, PortSel::PortB, 18, FunSel::Sel2).ok();
|
||||
port_mux(&mut dp.ioconfig, PortSel::PortB, 17, FunSel::Sel1).ok();
|
||||
port_mux(&mut dp.ioconfig, PortSel::PortB, 16, FunSel::Sel1).ok();
|
||||
}
|
||||
// Set the accelerometer chip select low in case the board slot is populated
|
||||
let mut accel_cs = pinsa.pa16.into_push_pull_output();
|
||||
accel_cs
|
||||
.set_high()
|
||||
.expect("Setting accelerometer chip select high failed");
|
||||
|
||||
let transfer_cfg = TransferConfig::<NoneT>::new(3.MHz(), spi::MODE_0, None, true, false);
|
||||
let spi = Spi::spib(
|
||||
dp.spib,
|
||||
(sck, miso, mosi),
|
||||
50.MHz(),
|
||||
spi_cfg,
|
||||
Some(&mut dp.sysconfig),
|
||||
Some(&transfer_cfg.downgrade()),
|
||||
)
|
||||
.downgrade();
|
||||
let delay_provider = CountDownTimer::new(&mut dp.sysconfig, 50.MHz(), dp.tim1);
|
||||
let spi_with_hwcs = SpiWithHwCs::new(spi, pinsa.pa17.into_funsel_2(), delay_provider);
|
||||
match EXAMPLE_MODE {
|
||||
ExampleMode::NotUsingEoc => spi_example_externally_clocked(spi_with_hwcs, delay),
|
||||
ExampleMode::UsingEoc => {
|
||||
spi_example_internally_clocked(spi_with_hwcs, delay, pinsa.pa14.into_floating_input());
|
||||
}
|
||||
ExampleMode::NotUsingEocWithDelay => {
|
||||
let delay_us = CountDownTimer::new(&mut dp.sysconfig, 50.MHz(), dp.tim2);
|
||||
spi_example_externally_clocked_with_delay(spi_with_hwcs, delay, delay_us);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[interrupt]
|
||||
#[allow(non_snake_case)]
|
||||
fn OC0() {
|
||||
default_ms_irq_handler();
|
||||
}
|
||||
|
||||
/// Use the SPI clock as the conversion clock
|
||||
fn spi_example_externally_clocked(spi: impl SpiDevice, mut delay: DelayMs) -> ! {
|
||||
let mut adc = max11619_externally_clocked_no_wakeup(spi)
|
||||
.expect("Creating externally clocked MAX11619 device failed");
|
||||
if READ_MODE == ReadMode::AverageN {
|
||||
adc.averaging(
|
||||
AveragingConversions::FourConversions,
|
||||
AveragingResults::FourResults,
|
||||
)
|
||||
.expect("Error setting up averaging register");
|
||||
}
|
||||
let mut cmd_buf: [u8; 32] = [0; 32];
|
||||
let mut counter = 0;
|
||||
loop {
|
||||
rprintln!("-- Measurement {} --", counter);
|
||||
|
||||
match READ_MODE {
|
||||
ReadMode::Single => {
|
||||
rprintln!("Reading single potentiometer channel");
|
||||
let pot_val = adc
|
||||
.read_single_channel(&mut cmd_buf, POTENTIOMETER_CHANNEL)
|
||||
.expect("Creating externally clocked MAX11619 ADC failed");
|
||||
rprintln!("Single channel read:");
|
||||
rprintln!("\tPotentiometer value: {}", pot_val);
|
||||
}
|
||||
ReadMode::Multiple => {
|
||||
let mut res_buf: [u16; 4] = [0; 4];
|
||||
adc.read_multiple_channels_0_to_n(
|
||||
&mut cmd_buf,
|
||||
&mut res_buf.iter_mut(),
|
||||
POTENTIOMETER_CHANNEL,
|
||||
)
|
||||
.expect("Multi-Channel read failed");
|
||||
print_res_buf(&res_buf);
|
||||
}
|
||||
ReadMode::MultipleNToHighest => {
|
||||
let mut res_buf: [u16; 2] = [0; 2];
|
||||
adc.read_multiple_channels_n_to_highest(
|
||||
&mut cmd_buf,
|
||||
&mut res_buf.iter_mut(),
|
||||
AN2_CHANNEL,
|
||||
)
|
||||
.expect("Multi-Channel read failed");
|
||||
rprintln!("Multi channel read from 2 to 3:");
|
||||
rprintln!("\tAN2 value: {}", res_buf[0]);
|
||||
rprintln!("\tAN3 / Potentiometer value: {}", res_buf[1]);
|
||||
}
|
||||
ReadMode::AverageN => {
|
||||
rprintln!("Scanning and averaging not possible for externally clocked mode");
|
||||
}
|
||||
}
|
||||
counter += 1;
|
||||
delay.delay_ms(500);
|
||||
}
|
||||
}
|
||||
|
||||
fn spi_example_externally_clocked_with_delay(
|
||||
spi: impl SpiDevice,
|
||||
mut delay: DelayMs,
|
||||
mut delay_us: impl DelayNs,
|
||||
) -> ! {
|
||||
let mut adc =
|
||||
max11619_externally_clocked_with_wakeup(spi).expect("Creating MAX116xx device failed");
|
||||
let mut cmd_buf: [u8; 32] = [0; 32];
|
||||
let mut counter = 0;
|
||||
loop {
|
||||
rprintln!("-- Measurement {} --", counter);
|
||||
|
||||
match READ_MODE {
|
||||
ReadMode::Single => {
|
||||
rprintln!("Reading single potentiometer channel");
|
||||
let pot_val = adc
|
||||
.read_single_channel(&mut cmd_buf, POTENTIOMETER_CHANNEL, &mut delay_us)
|
||||
.expect("Creating externally clocked MAX11619 ADC failed");
|
||||
rprintln!("Single channel read:");
|
||||
rprintln!("\tPotentiometer value: {}", pot_val);
|
||||
}
|
||||
ReadMode::Multiple => {
|
||||
let mut res_buf: [u16; 4] = [0; 4];
|
||||
adc.read_multiple_channels_0_to_n(
|
||||
&mut cmd_buf,
|
||||
&mut res_buf.iter_mut(),
|
||||
POTENTIOMETER_CHANNEL,
|
||||
&mut delay_us,
|
||||
)
|
||||
.expect("Multi-Channel read failed");
|
||||
print_res_buf(&res_buf);
|
||||
}
|
||||
ReadMode::MultipleNToHighest => {
|
||||
let mut res_buf: [u16; 2] = [0; 2];
|
||||
adc.read_multiple_channels_n_to_highest(
|
||||
&mut cmd_buf,
|
||||
&mut res_buf.iter_mut(),
|
||||
AN2_CHANNEL,
|
||||
&mut delay_us,
|
||||
)
|
||||
.expect("Multi-Channel read failed");
|
||||
rprintln!("Multi channel read from 2 to 3:");
|
||||
rprintln!("\tAN2 value: {}", res_buf[0]);
|
||||
rprintln!("\tAN3 / Potentiometer value: {}", res_buf[1]);
|
||||
}
|
||||
ReadMode::AverageN => {
|
||||
rprintln!("Scanning and averaging not possible for externally clocked mode");
|
||||
}
|
||||
}
|
||||
counter += 1;
|
||||
delay.delay_ms(500);
|
||||
}
|
||||
}
|
||||
|
||||
/// This function uses the EOC pin to determine whether the conversion finished
|
||||
fn spi_example_internally_clocked(spi: impl SpiDevice, mut delay: DelayMs, eoc_pin: EocPin) -> ! {
|
||||
let mut adc = max11619_internally_clocked(
|
||||
spi,
|
||||
eoc_pin,
|
||||
VoltageRefMode::ExternalSingleEndedNoWakeupDelay,
|
||||
)
|
||||
.expect("Creating MAX116xx device failed");
|
||||
let mut counter = 0;
|
||||
loop {
|
||||
rprintln!("-- Measurement {} --", counter);
|
||||
|
||||
match READ_MODE {
|
||||
ReadMode::Single => {
|
||||
adc.request_single_channel(POTENTIOMETER_CHANNEL)
|
||||
.expect("Requesting single channel value failed");
|
||||
|
||||
let pot_val = nb::block!(adc.get_single_channel())
|
||||
.expect("Reading single channel value failed");
|
||||
rprintln!("\tPotentiometer value: {}", pot_val);
|
||||
}
|
||||
ReadMode::Multiple => {
|
||||
adc.request_multiple_channels_0_to_n(POTENTIOMETER_CHANNEL)
|
||||
.expect("Requesting single channel value failed");
|
||||
let mut res_buf: [u16; 4] = [0; 4];
|
||||
nb::block!(adc.get_multi_channel(&mut res_buf.iter_mut()))
|
||||
.expect("Requesting multiple channel values failed");
|
||||
print_res_buf(&res_buf);
|
||||
}
|
||||
ReadMode::MultipleNToHighest => {
|
||||
adc.request_multiple_channels_n_to_highest(AN2_CHANNEL)
|
||||
.expect("Requesting single channel value failed");
|
||||
let mut res_buf: [u16; 4] = [0; 4];
|
||||
nb::block!(adc.get_multi_channel(&mut res_buf.iter_mut()))
|
||||
.expect("Requesting multiple channel values failed");
|
||||
rprintln!("Multi channel read from 2 to 3:");
|
||||
rprintln!("\tAN2 value: {}", res_buf[0]);
|
||||
rprintln!("\tAN3 / Potentiometer value: {}", res_buf[1]);
|
||||
}
|
||||
ReadMode::AverageN => {
|
||||
adc.request_channel_n_repeatedly(POTENTIOMETER_CHANNEL)
|
||||
.expect("Reading channel multiple times failed");
|
||||
let mut res_buf: [u16; 16] = [0; 16];
|
||||
nb::block!(adc.get_multi_channel(&mut res_buf.iter_mut()))
|
||||
.expect("Requesting multiple channel values failed");
|
||||
rprintln!("Reading potentiometer 4 times");
|
||||
rprintln!("\tValue 0: {}", res_buf[0]);
|
||||
rprintln!("\tValue 1: {}", res_buf[1]);
|
||||
rprintln!("\tValue 2: {}", res_buf[2]);
|
||||
rprintln!("\tValue 3: {}", res_buf[3]);
|
||||
}
|
||||
}
|
||||
|
||||
counter += 1;
|
||||
delay.delay_ms(500);
|
||||
}
|
||||
}
|
||||
|
||||
fn print_res_buf(buf: &[u16; 4]) {
|
||||
rprintln!("Multi channel read from 0 to 3:");
|
||||
rprintln!("\tAN0 value: {}", buf[0]);
|
||||
rprintln!("\tAN1 value: {}", buf[1]);
|
||||
rprintln!("\tAN2 value: {}", buf[2]);
|
||||
rprintln!("\tAN3 / Potentiometer value: {}", buf[3]);
|
||||
}
|
Reference in New Issue
Block a user