move to updated API
This commit is contained in:
@ -15,10 +15,11 @@ cortex-m = { version = "0.7", features = ["critical-section-single-core"] }
|
||||
cortex-m-rt = "0.7"
|
||||
embedded-hal = "1"
|
||||
nb = "1"
|
||||
bitfield = ">=0.17, <=0.19"
|
||||
bitbybit = "1.3"
|
||||
arbitrary-int = "1.3"
|
||||
max116xx-10bit = "0.3"
|
||||
|
||||
va108xx-hal = { version = ">=0.10, <=0.11", features = ["rt"] }
|
||||
va108xx-hal = { version = ">=0.10, <=0.11", path = "../va108xx-hal", features = ["rt"] }
|
||||
|
||||
[features]
|
||||
rt = ["va108xx-hal/rt"]
|
||||
|
@ -4,16 +4,16 @@ use cortex_m_rt::entry;
|
||||
use embedded_hal::delay::DelayNs;
|
||||
use panic_rtt_target as _;
|
||||
use rtt_target::{rprintln, rtt_init_print};
|
||||
use va108xx_hal::{pac, prelude::*, timer::set_up_ms_delay_provider};
|
||||
use va108xx_hal::{pac, prelude::*, timer::CountdownTimer};
|
||||
use vorago_reb1::temp_sensor::Adt75TempSensor;
|
||||
|
||||
#[entry]
|
||||
fn main() -> ! {
|
||||
rtt_init_print!();
|
||||
rprintln!("-- Vorago Temperature Sensor and I2C Example --");
|
||||
let mut dp = pac::Peripherals::take().unwrap();
|
||||
let mut delay = set_up_ms_delay_provider(&mut dp.sysconfig, 50.MHz(), dp.tim0);
|
||||
let mut temp_sensor = Adt75TempSensor::new(&mut dp.sysconfig, 50.MHz(), dp.i2ca)
|
||||
let dp = pac::Peripherals::take().unwrap();
|
||||
let mut delay = CountdownTimer::new(50.MHz(), dp.tim0);
|
||||
let mut temp_sensor = Adt75TempSensor::new(50.MHz(), dp.i2ca)
|
||||
.expect("Creating temperature sensor struct failed");
|
||||
loop {
|
||||
let temp = temp_sensor
|
||||
|
@ -9,13 +9,14 @@ use embedded_hal::delay::DelayNs;
|
||||
use embedded_hal::spi::{SpiBus, MODE_3};
|
||||
use panic_rtt_target as _;
|
||||
use rtt_target::{rprintln, rtt_init_print};
|
||||
use va108xx_hal::spi::SpiClkConfig;
|
||||
use va108xx_hal::gpio::{Output, PinState};
|
||||
use va108xx_hal::pins::PinsA;
|
||||
use va108xx_hal::spi::{configure_pin_as_hw_cs_pin, SpiClkConfig};
|
||||
use va108xx_hal::timer::CountdownTimer;
|
||||
use va108xx_hal::{
|
||||
gpio::PinsA,
|
||||
pac,
|
||||
prelude::*,
|
||||
spi::{Spi, SpiConfig},
|
||||
timer::set_up_ms_delay_provider,
|
||||
};
|
||||
|
||||
const READ_MASK: u8 = 1 << 7;
|
||||
@ -29,19 +30,19 @@ const PWR_MEASUREMENT_MODE_MASK: u8 = 1 << 3;
|
||||
fn main() -> ! {
|
||||
rtt_init_print!();
|
||||
rprintln!("-- Vorago Accelerometer Example --");
|
||||
let mut dp = pac::Peripherals::take().unwrap();
|
||||
let mut delay = set_up_ms_delay_provider(&mut dp.sysconfig, 50.MHz(), dp.tim0);
|
||||
let pinsa = PinsA::new(&mut dp.sysconfig, dp.porta);
|
||||
let dp = pac::Peripherals::take().unwrap();
|
||||
let pinsa = PinsA::new(dp.porta);
|
||||
let mut delay = CountdownTimer::new(50.MHz(), dp.tim0);
|
||||
let (sck, mosi, miso) = (
|
||||
pinsa.pa20.into_funsel_2(),
|
||||
pinsa.pa19.into_funsel_2(),
|
||||
pinsa.pa18.into_funsel_2(),
|
||||
pinsa.pa20,
|
||||
pinsa.pa19,
|
||||
pinsa.pa18,
|
||||
);
|
||||
let cs_pin = pinsa.pa16.into_funsel_2();
|
||||
let cs_pin = pinsa.pa16;
|
||||
let hw_cs_id = configure_pin_as_hw_cs_pin(cs_pin);
|
||||
|
||||
// Need to set the ADC chip select low
|
||||
let mut adc_cs = pinsa.pa17.into_push_pull_output();
|
||||
adc_cs.set_high();
|
||||
Output::new(pinsa.pa17, PinState::Low);
|
||||
|
||||
let spi_cfg = SpiConfig::default()
|
||||
.clk_cfg(
|
||||
@ -50,13 +51,12 @@ fn main() -> ! {
|
||||
.mode(MODE_3)
|
||||
.slave_output_disable(true);
|
||||
let mut spi = Spi::new(
|
||||
&mut dp.sysconfig,
|
||||
50.MHz(),
|
||||
dp.spib,
|
||||
(sck, miso, mosi),
|
||||
spi_cfg,
|
||||
);
|
||||
spi.cfg_hw_cs_with_pin(&cs_pin);
|
||||
).unwrap();
|
||||
spi.cfg_hw_cs(hw_cs_id);
|
||||
|
||||
let mut tx_rx_buf: [u8; 3] = [0; 3];
|
||||
tx_rx_buf[0] = READ_MASK | DEVID_REG;
|
||||
|
@ -10,10 +10,10 @@ use panic_rtt_target as _;
|
||||
use rtt_target::{rprintln, rtt_init_print};
|
||||
use va108xx_hal::{
|
||||
clock::{set_clk_div_register, FilterClkSel},
|
||||
gpio::{FilterType, InterruptEdge, PinsA},
|
||||
gpio::{FilterType, InterruptEdge},
|
||||
pac::{self, interrupt},
|
||||
prelude::*,
|
||||
timer::{default_ms_irq_handler, set_up_ms_tick, InterruptConfig},
|
||||
pins::PinsA,
|
||||
timer::InterruptConfig,
|
||||
};
|
||||
use vorago_reb1::button::Button;
|
||||
use vorago_reb1::leds::Leds;
|
||||
@ -35,18 +35,18 @@ fn main() -> ! {
|
||||
rtt_init_print!();
|
||||
rprintln!("-- Vorago Button IRQ Example --");
|
||||
let mut dp = pac::Peripherals::take().unwrap();
|
||||
let pinsa = PinsA::new(&mut dp.sysconfig, dp.porta);
|
||||
let pinsa = PinsA::new(dp.porta);
|
||||
let edge_irq = match PRESS_MODE {
|
||||
PressMode::Toggle => InterruptEdge::HighToLow,
|
||||
PressMode::Keep => InterruptEdge::BothEdges,
|
||||
};
|
||||
|
||||
// Configure an edge interrupt on the button and route it to interrupt vector 15
|
||||
let mut button = Button::new(pinsa.pa11.into_floating_input());
|
||||
let mut button = Button::new(pinsa.pa11);
|
||||
|
||||
if PRESS_MODE == PressMode::Toggle {
|
||||
// This filter debounces the switch for edge based interrupts
|
||||
button.configure_filter_type(FilterType::FilterFourClockCycles, FilterClkSel::Clk1);
|
||||
button.configure_filter_type(FilterType::FilterFourCycles, FilterClkSel::Clk1);
|
||||
set_clk_div_register(&mut dp.sysconfig, FilterClkSel::Clk1, 50_000);
|
||||
}
|
||||
button.configure_and_enable_edge_interrupt(
|
||||
@ -54,18 +54,7 @@ fn main() -> ! {
|
||||
InterruptConfig::new(pac::interrupt::OC15, true, true),
|
||||
);
|
||||
|
||||
set_up_ms_tick(
|
||||
InterruptConfig::new(pac::Interrupt::OC0, true, true),
|
||||
&mut dp.sysconfig,
|
||||
Some(&mut dp.irqsel),
|
||||
50.MHz(),
|
||||
dp.tim0,
|
||||
);
|
||||
let mut leds = Leds::new(
|
||||
pinsa.pa10.into_push_pull_output(),
|
||||
pinsa.pa7.into_push_pull_output(),
|
||||
pinsa.pa6.into_push_pull_output(),
|
||||
);
|
||||
let mut leds = Leds::new(pinsa.pa10, pinsa.pa7, pinsa.pa6);
|
||||
for led in leds.iter_mut() {
|
||||
led.off();
|
||||
}
|
||||
@ -79,11 +68,6 @@ fn main() -> ! {
|
||||
}
|
||||
}
|
||||
|
||||
#[interrupt]
|
||||
fn OC0() {
|
||||
default_ms_irq_handler();
|
||||
}
|
||||
|
||||
#[interrupt]
|
||||
fn OC15() {
|
||||
cortex_m::interrupt::free(|cs| {
|
||||
|
@ -9,7 +9,13 @@
|
||||
use cortex_m_rt::entry;
|
||||
use embedded_hal::delay::DelayNs;
|
||||
use panic_halt as _;
|
||||
use va108xx_hal::{gpio::PinsA, pac, prelude::*, timer::set_up_ms_delay_provider};
|
||||
use va108xx_hal::{
|
||||
gpio::{Output, PinState},
|
||||
pac,
|
||||
pins::PinsA,
|
||||
prelude::*,
|
||||
timer::CountdownTimer,
|
||||
};
|
||||
use vorago_reb1::leds::Leds;
|
||||
|
||||
// REB LED pin definitions. All on port A
|
||||
@ -26,7 +32,7 @@ enum LibType {
|
||||
|
||||
#[entry]
|
||||
fn main() -> ! {
|
||||
let mut dp = pac::Peripherals::take().unwrap();
|
||||
let dp = pac::Peripherals::take().unwrap();
|
||||
|
||||
let lib_type = LibType::Bsp;
|
||||
|
||||
@ -60,11 +66,11 @@ fn main() -> ! {
|
||||
}
|
||||
}
|
||||
LibType::Hal => {
|
||||
let pins = PinsA::new(&mut dp.sysconfig, dp.porta);
|
||||
let mut led1 = pins.pa10.into_readable_push_pull_output();
|
||||
let mut led2 = pins.pa7.into_readable_push_pull_output();
|
||||
let mut led3 = pins.pa6.into_readable_push_pull_output();
|
||||
let mut delay = set_up_ms_delay_provider(&mut dp.sysconfig, 50.MHz(), dp.tim0);
|
||||
let pins = PinsA::new(dp.porta);
|
||||
let mut led1 = Output::new(pins.pa10, PinState::Low);
|
||||
let mut led2 = Output::new(pins.pa7, PinState::Low);
|
||||
let mut led3 = Output::new(pins.pa6, PinState::Low);
|
||||
let mut delay = CountdownTimer::new(50.MHz(), dp.tim0);
|
||||
for _ in 0..10 {
|
||||
led1.set_low();
|
||||
led2.set_low();
|
||||
@ -83,13 +89,9 @@ fn main() -> ! {
|
||||
}
|
||||
}
|
||||
LibType::Bsp => {
|
||||
let pinsa = PinsA::new(&mut dp.sysconfig, dp.porta);
|
||||
let mut leds = Leds::new(
|
||||
pinsa.pa10.into_push_pull_output(),
|
||||
pinsa.pa7.into_push_pull_output(),
|
||||
pinsa.pa6.into_push_pull_output(),
|
||||
);
|
||||
let mut delay = set_up_ms_delay_provider(&mut dp.sysconfig, 50.MHz(), dp.tim0);
|
||||
let pinsa = PinsA::new(dp.porta);
|
||||
let mut leds = Leds::new(pinsa.pa10, pinsa.pa7, pinsa.pa6);
|
||||
let mut delay = CountdownTimer::new(50.MHz(), dp.tim0);
|
||||
for _ in 0..10 {
|
||||
// Blink all LEDs quickly
|
||||
for led in leds.iter_mut() {
|
||||
|
@ -5,16 +5,18 @@
|
||||
//! - [Button Blinky with IRQs](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/vorago-reb1/examples/blinky-button-irq.rs)
|
||||
//! - [Button Blinky with IRQs and RTIC](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/vorago-reb1/examples/blinky-button-rtic.rs)
|
||||
use va108xx_hal::{
|
||||
gpio::{FilterClkSel, FilterType, InputFloating, InterruptEdge, InterruptLevel, Pin, PA11},
|
||||
clock::FilterClkSel,
|
||||
gpio::{FilterType, Input, InterruptEdge, InterruptLevel, Pin},
|
||||
pins::Pa11,
|
||||
InterruptConfig,
|
||||
};
|
||||
|
||||
#[derive(Debug)]
|
||||
pub struct Button(pub Pin<PA11, InputFloating>);
|
||||
pub struct Button(pub Input);
|
||||
|
||||
impl Button {
|
||||
pub fn new(pin: Pin<PA11, InputFloating>) -> Button {
|
||||
Button(pin)
|
||||
pub fn new(pin: Pin<Pa11>) -> Button {
|
||||
Button(Input::new_floating(pin))
|
||||
}
|
||||
|
||||
#[inline]
|
||||
|
@ -6,20 +6,20 @@
|
||||
//! - [Button Blinky using IRQs](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/vorago-reb1/examples/blinky-button-irq.rs)
|
||||
//! - [Button Blinky using IRQs and RTIC](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/vorago-reb1/examples/blinky-button-rtic.rs)
|
||||
use va108xx_hal::{
|
||||
gpio::dynpin::DynPin,
|
||||
gpio::pin::{Pin, PushPullOutput, PA10, PA6, PA7},
|
||||
gpio::{Output, PinState},
|
||||
pins::{Pa10, Pa6, Pa7, Pin},
|
||||
};
|
||||
|
||||
pub type LD2 = Pin<PA10, PushPullOutput>;
|
||||
pub type LD3 = Pin<PA7, PushPullOutput>;
|
||||
pub type LD4 = Pin<PA6, PushPullOutput>;
|
||||
|
||||
#[derive(Debug)]
|
||||
pub struct Leds(pub [Led; 3]);
|
||||
|
||||
impl Leds {
|
||||
pub fn new(led_pin1: LD2, led_pin2: LD3, led_pin3: LD4) -> Leds {
|
||||
Leds([led_pin1.into(), led_pin2.into(), led_pin3.into()])
|
||||
pub fn new(led_pin1: Pin<Pa10>, led_pin2: Pin<Pa7>, led_pin3: Pin<Pa6>) -> Leds {
|
||||
Leds([
|
||||
Led(Output::new(led_pin1, PinState::Low)),
|
||||
Led(Output::new(led_pin2, PinState::Low)),
|
||||
Led(Output::new(led_pin3, PinState::Low)),
|
||||
])
|
||||
}
|
||||
}
|
||||
|
||||
@ -52,38 +52,24 @@ impl core::ops::IndexMut<usize> for Leds {
|
||||
}
|
||||
|
||||
#[derive(Debug)]
|
||||
pub struct Led(pub DynPin);
|
||||
|
||||
macro_rules! ctor {
|
||||
($($ldx:ident),+) => {
|
||||
$(
|
||||
impl From<$ldx> for Led {
|
||||
fn from(led: $ldx) -> Self {
|
||||
Led(led.into())
|
||||
}
|
||||
}
|
||||
)+
|
||||
}
|
||||
}
|
||||
|
||||
ctor!(LD2, LD3, LD4);
|
||||
pub struct Led(Output);
|
||||
|
||||
impl Led {
|
||||
/// Turns the LED off. Setting the pin high actually turns the LED off
|
||||
#[inline]
|
||||
pub fn off(&mut self) {
|
||||
self.0.set_high().ok();
|
||||
self.0.set_high();
|
||||
}
|
||||
|
||||
/// Turns the LED on. Setting the pin low actually turns the LED on
|
||||
#[inline]
|
||||
pub fn on(&mut self) {
|
||||
self.0.set_low().ok();
|
||||
self.0.set_low();
|
||||
}
|
||||
|
||||
/// Toggles the LED
|
||||
#[inline]
|
||||
pub fn toggle(&mut self) {
|
||||
self.0.toggle().ok();
|
||||
self.0.toggle();
|
||||
}
|
||||
}
|
||||
|
@ -7,20 +7,25 @@
|
||||
//! # Example
|
||||
//!
|
||||
//! - [REB1 EEPROM example](https://egit.irs.uni-stuttgart.de/rust/va108xx-rs/src/branch/main/vorago-reb1/examples/nvm.rs)
|
||||
use arbitrary_int::{u2, u3};
|
||||
use core::convert::Infallible;
|
||||
use embedded_hal::spi::SpiBus;
|
||||
|
||||
pub const PAGE_SIZE: usize = 256;
|
||||
|
||||
bitfield::bitfield! {
|
||||
pub struct StatusReg(u8);
|
||||
impl Debug;
|
||||
u8;
|
||||
pub status_register_write_protect, _: 7;
|
||||
pub zero_segment, _: 6, 4;
|
||||
pub block_protection_bits, set_block_protection_bits: 3, 2;
|
||||
pub write_enable_latch, _: 1;
|
||||
pub write_in_progress, _: 0;
|
||||
#[bitbybit::bitfield(u8)]
|
||||
#[derive(Debug)]
|
||||
pub struct StatusReg {
|
||||
#[bit(7, r)]
|
||||
status_register_write_protect: bool,
|
||||
#[bits(4..=6, r)]
|
||||
zero_segment: u3,
|
||||
#[bits(2..=3, rw)]
|
||||
block_protection_bits: u2,
|
||||
#[bit(1, r)]
|
||||
write_enable_latch: bool,
|
||||
#[bit(0, r)]
|
||||
write_in_progress: bool,
|
||||
}
|
||||
|
||||
// Registers.
|
||||
@ -43,10 +48,10 @@ use regs::*;
|
||||
use va108xx_hal::{
|
||||
pac,
|
||||
prelude::*,
|
||||
spi::{RomMiso, RomMosi, RomSck, Spi, SpiClkConfig, SpiConfig, BMSTART_BMSTOP_MASK},
|
||||
spi::{Spi, SpiClkConfig, SpiConfig, SpiLowLevel, BMSTART_BMSTOP_MASK},
|
||||
};
|
||||
|
||||
pub type RomSpi = Spi<pac::Spic, (RomSck, RomMiso, RomMosi), u8>;
|
||||
pub type RomSpi = Spi<u8>;
|
||||
|
||||
/// Driver for the ST device M95M01 EEPROM memory.
|
||||
///
|
||||
@ -59,14 +64,13 @@ pub struct M95M01 {
|
||||
pub struct PageBoundaryExceededError;
|
||||
|
||||
impl M95M01 {
|
||||
pub fn new(syscfg: &mut pac::Sysconfig, sys_clk: impl Into<Hertz>, spi: pac::Spic) -> Self {
|
||||
let spi = RomSpi::new(
|
||||
syscfg,
|
||||
pub fn new(sys_clk: Hertz, spi: pac::Spic) -> Self {
|
||||
let spi = RomSpi::new_for_rom(
|
||||
sys_clk,
|
||||
spi,
|
||||
(RomSck, RomMiso, RomMosi),
|
||||
SpiConfig::default().clk_cfg(SpiClkConfig::new(2, 4)),
|
||||
);
|
||||
)
|
||||
.unwrap();
|
||||
let mut spi_dev = Self { spi };
|
||||
spi_dev.clear_block_protection().unwrap();
|
||||
spi_dev
|
||||
@ -74,7 +78,7 @@ impl M95M01 {
|
||||
|
||||
pub fn release(mut self) -> pac::Spic {
|
||||
self.set_block_protection().unwrap();
|
||||
self.spi.release().0
|
||||
unsafe { pac::Spic::steal() }
|
||||
}
|
||||
|
||||
// Wait until the write-in-progress state is cleared. This exposes a [nb] API, so this function
|
||||
@ -90,7 +94,7 @@ impl M95M01 {
|
||||
pub fn read_status_reg(&mut self) -> Result<StatusReg, Infallible> {
|
||||
let mut write_read: [u8; 2] = [regs::RDSR, 0x00];
|
||||
self.spi.transfer_in_place(&mut write_read)?;
|
||||
Ok(StatusReg(write_read[1]))
|
||||
Ok(StatusReg::new_with_raw_value(write_read[1]))
|
||||
}
|
||||
|
||||
pub fn write_enable(&mut self) -> Result<(), Infallible> {
|
||||
@ -104,10 +108,10 @@ impl M95M01 {
|
||||
}
|
||||
|
||||
pub fn set_block_protection(&mut self) -> Result<(), Infallible> {
|
||||
let mut reg = StatusReg(0);
|
||||
reg.set_block_protection_bits(0b11);
|
||||
let mut reg = StatusReg::new_with_raw_value(0);
|
||||
reg.set_block_protection_bits(u2::new(0b11));
|
||||
self.write_enable()?;
|
||||
self.spi.write(&[WRSR, reg.0])
|
||||
self.spi.write(&[WRSR, reg.raw_value()])
|
||||
}
|
||||
|
||||
fn common_init_write_and_read(&mut self, address: usize, reg: u8) -> Result<(), Infallible> {
|
||||
|
@ -9,7 +9,7 @@ use max116xx_10bit::{
|
||||
Error, ExternallyClocked, InternallyClockedInternallyTimedSerialInterface, Max116xx10Bit,
|
||||
Max116xx10BitEocExt, VoltageRefMode, WithWakeupDelay, WithoutWakeupDelay,
|
||||
};
|
||||
use va108xx_hal::gpio::{Floating, Input, Pin, PA14};
|
||||
use va108xx_hal::gpio::Input;
|
||||
|
||||
pub type Max11619ExternallyClockedNoWakeup<Spi> =
|
||||
Max116xx10Bit<Spi, ExternallyClocked, WithoutWakeupDelay>;
|
||||
@ -17,7 +17,6 @@ pub type Max11619ExternallyClockedWithWakeup<Spi> =
|
||||
Max116xx10Bit<Spi, ExternallyClocked, WithWakeupDelay>;
|
||||
pub type Max11619InternallyClocked<Spi, Eoc> =
|
||||
Max116xx10BitEocExt<Spi, Eoc, InternallyClockedInternallyTimedSerialInterface>;
|
||||
pub type EocPin = Pin<PA14, Input<Floating>>;
|
||||
|
||||
pub const AN0_CHANNEL: u8 = 0;
|
||||
pub const AN1_CHANNEL: u8 = 1;
|
||||
@ -44,9 +43,9 @@ pub fn max11619_externally_clocked_with_wakeup<Spi: SpiDevice>(
|
||||
|
||||
pub fn max11619_internally_clocked<Spi: SpiDevice>(
|
||||
spi: Spi,
|
||||
eoc: EocPin,
|
||||
eoc: Input,
|
||||
v_ref: VoltageRefMode,
|
||||
) -> Result<Max11619InternallyClocked<Spi, EocPin>, Error<Spi::Error, Infallible>> {
|
||||
) -> Result<Max11619InternallyClocked<Spi, Input>, Error<Spi::Error, Infallible>> {
|
||||
let mut adc = Max116xx10Bit::max11619(spi)?
|
||||
.into_int_clkd_int_timed_through_ser_if_without_wakeup(v_ref, eoc)?;
|
||||
adc.reset(false)?;
|
||||
|
@ -48,15 +48,10 @@ impl From<Error> for AdtInitError {
|
||||
}
|
||||
|
||||
impl Adt75TempSensor {
|
||||
pub fn new(
|
||||
sys_cfg: &mut pac::Sysconfig,
|
||||
sys_clk: impl Into<Hertz> + Copy,
|
||||
i2ca: pac::I2ca,
|
||||
) -> Result<Self, Error> {
|
||||
pub fn new(sys_clk: Hertz, i2ca: pac::I2ca) -> Result<Self, Error> {
|
||||
let mut sensor = Adt75TempSensor {
|
||||
// The master construction can not fail for regular I2C speed.
|
||||
sensor_if: I2cMaster::new(
|
||||
sys_cfg,
|
||||
sys_clk,
|
||||
i2ca,
|
||||
MasterConfig::default(),
|
||||
|
Reference in New Issue
Block a user