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:
66
vorago-reb1/src/button.rs
Normal file
66
vorago-reb1/src/button.rs
Normal file
@ -0,0 +1,66 @@
|
||||
//! # API for the REB1 button
|
||||
//!
|
||||
//! ## Examples
|
||||
//!
|
||||
//! - [Button Blinky with IRQs](https://egit.irs.uni-stuttgart.de/rust/vorago-reb1/src/branch/main/examples/blinky-button-irq.rs)
|
||||
//! - [Button Blinky with IRQs and RTIC](https://egit.irs.uni-stuttgart.de/rust/vorago-reb1/src/branch/main/examples/blinky-button-rtic.rs)
|
||||
use embedded_hal::digital::InputPin;
|
||||
use va108xx_hal::{
|
||||
gpio::{FilterClkSel, FilterType, InputFloating, InterruptEdge, InterruptLevel, Pin, PA11},
|
||||
pac, IrqCfg,
|
||||
};
|
||||
|
||||
pub struct Button {
|
||||
button: Pin<PA11, InputFloating>,
|
||||
}
|
||||
|
||||
impl Button {
|
||||
pub fn new(pin: Pin<PA11, InputFloating>) -> Button {
|
||||
Button { button: pin }
|
||||
}
|
||||
|
||||
#[inline]
|
||||
pub fn pressed(&mut self) -> bool {
|
||||
self.button.is_low().ok().unwrap()
|
||||
}
|
||||
|
||||
#[inline]
|
||||
pub fn released(&mut self) -> bool {
|
||||
self.button.is_high().ok().unwrap()
|
||||
}
|
||||
|
||||
/// Configures an IRQ on edge.
|
||||
pub fn edge_irq(
|
||||
mut self,
|
||||
edge_type: InterruptEdge,
|
||||
irq_cfg: IrqCfg,
|
||||
syscfg: Option<&mut pac::Sysconfig>,
|
||||
irqsel: Option<&mut pac::Irqsel>,
|
||||
) -> Self {
|
||||
self.button = self
|
||||
.button
|
||||
.interrupt_edge(edge_type, irq_cfg, syscfg, irqsel);
|
||||
self
|
||||
}
|
||||
|
||||
/// Configures an IRQ on level.
|
||||
pub fn level_irq(
|
||||
mut self,
|
||||
level: InterruptLevel,
|
||||
irq_cfg: IrqCfg,
|
||||
syscfg: Option<&mut pac::Sysconfig>,
|
||||
irqsel: Option<&mut pac::Irqsel>,
|
||||
) -> Self {
|
||||
self.button = self.button.interrupt_level(level, irq_cfg, syscfg, irqsel);
|
||||
self
|
||||
}
|
||||
|
||||
/// Configures a filter on the button. This can be useful for debouncing the switch.
|
||||
///
|
||||
/// Please note that you still have to set a clock divisor yourself using the
|
||||
/// [`va108xx_hal::clock::set_clk_div_register`] function in order for this to work.
|
||||
pub fn filter_type(mut self, filter: FilterType, clksel: FilterClkSel) -> Self {
|
||||
self.button = self.button.filter_type(filter, clksel);
|
||||
self
|
||||
}
|
||||
}
|
96
vorago-reb1/src/leds.rs
Normal file
96
vorago-reb1/src/leds.rs
Normal file
@ -0,0 +1,96 @@
|
||||
//! # API for using the REB1 LEDs
|
||||
//!
|
||||
//! ## Examples
|
||||
//!
|
||||
//! - [LED example](https://egit.irs.uni-stuttgart.de/rust/vorago-reb1/src/branch/main/examples/blinky-leds.rs)
|
||||
//! - [Button Blinky using IRQs](https://egit.irs.uni-stuttgart.de/rust/vorago-reb1/src/branch/main/examples/blinky-button-irq.rs)
|
||||
//! - [Button Blinky using IRQs and RTIC](https://egit.irs.uni-stuttgart.de/rust/vorago-reb1/src/branch/main/examples/blinky-button-rtic.rs)
|
||||
use embedded_hal::digital::OutputPin;
|
||||
use va108xx_hal::{
|
||||
gpio::dynpins::DynPin,
|
||||
gpio::pins::{Pin, PushPullOutput, PA10, PA6, PA7},
|
||||
};
|
||||
|
||||
pub type LD2 = Pin<PA10, PushPullOutput>;
|
||||
pub type LD3 = Pin<PA7, PushPullOutput>;
|
||||
pub type LD4 = Pin<PA6, PushPullOutput>;
|
||||
|
||||
pub struct Leds {
|
||||
leds: [Led; 3],
|
||||
}
|
||||
|
||||
impl Leds {
|
||||
pub fn new(led_pin1: LD2, led_pin2: LD3, led_pin3: LD4) -> Leds {
|
||||
Leds {
|
||||
leds: [led_pin1.into(), led_pin2.into(), led_pin3.into()],
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl core::ops::Deref for Leds {
|
||||
type Target = [Led];
|
||||
|
||||
fn deref(&self) -> &[Led] {
|
||||
&self.leds
|
||||
}
|
||||
}
|
||||
|
||||
impl core::ops::DerefMut for Leds {
|
||||
fn deref_mut(&mut self) -> &mut [Led] {
|
||||
&mut self.leds
|
||||
}
|
||||
}
|
||||
|
||||
impl core::ops::Index<usize> for Leds {
|
||||
type Output = Led;
|
||||
|
||||
fn index(&self, i: usize) -> &Led {
|
||||
&self.leds[i]
|
||||
}
|
||||
}
|
||||
|
||||
impl core::ops::IndexMut<usize> for Leds {
|
||||
fn index_mut(&mut self, i: usize) -> &mut Led {
|
||||
&mut self.leds[i]
|
||||
}
|
||||
}
|
||||
|
||||
pub struct Led {
|
||||
pin: DynPin,
|
||||
}
|
||||
|
||||
macro_rules! ctor {
|
||||
($($ldx:ident),+) => {
|
||||
$(
|
||||
impl From<$ldx> for Led {
|
||||
fn from(led: $ldx) -> Self {
|
||||
Led {
|
||||
pin: led.into()
|
||||
}
|
||||
}
|
||||
}
|
||||
)+
|
||||
}
|
||||
}
|
||||
|
||||
ctor!(LD2, LD3, LD4);
|
||||
|
||||
impl Led {
|
||||
/// Turns the LED off. Setting the pin high actually turns the LED off
|
||||
#[inline]
|
||||
pub fn off(&mut self) {
|
||||
self.pin.set_high().ok();
|
||||
}
|
||||
|
||||
/// Turns the LED on. Setting the pin low actually turns the LED on
|
||||
#[inline]
|
||||
pub fn on(&mut self) {
|
||||
self.pin.set_low().ok();
|
||||
}
|
||||
|
||||
/// Toggles the LED
|
||||
#[inline]
|
||||
pub fn toggle(&mut self) {
|
||||
self.pin.toggle_with_toggle_reg().ok();
|
||||
}
|
||||
}
|
6
vorago-reb1/src/lib.rs
Normal file
6
vorago-reb1/src/lib.rs
Normal file
@ -0,0 +1,6 @@
|
||||
#![no_std]
|
||||
|
||||
pub mod button;
|
||||
pub mod leds;
|
||||
pub mod max11619;
|
||||
pub mod temp_sensor;
|
55
vorago-reb1/src/max11619.rs
Normal file
55
vorago-reb1/src/max11619.rs
Normal file
@ -0,0 +1,55 @@
|
||||
//! This module provides a thin REB1 specific layer on top of the `max116xx_10bit` driver crate
|
||||
//!
|
||||
//! ## Examples
|
||||
//!
|
||||
//! - [ADC example](https://egit.irs.uni-stuttgart.de/rust/vorago-reb1/src/branch/main/examples/max11619-adc.rs)
|
||||
use core::convert::Infallible;
|
||||
use embedded_hal::spi::SpiDevice;
|
||||
use max116xx_10bit::{
|
||||
Error, ExternallyClocked, InternallyClockedInternallyTimedSerialInterface, Max116xx10Bit,
|
||||
Max116xx10BitEocExt, VoltageRefMode, WithWakeupDelay, WithoutWakeupDelay,
|
||||
};
|
||||
use va108xx_hal::gpio::{Floating, Input, Pin, PA14};
|
||||
|
||||
pub type Max11619ExternallyClockedNoWakeup<Spi> =
|
||||
Max116xx10Bit<Spi, ExternallyClocked, WithoutWakeupDelay>;
|
||||
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;
|
||||
pub const AN2_CHANNEL: u8 = 2;
|
||||
pub const POTENTIOMETER_CHANNEL: u8 = 3;
|
||||
|
||||
pub fn max11619_externally_clocked_no_wakeup<Spi: SpiDevice>(
|
||||
spi: Spi,
|
||||
) -> Result<Max11619ExternallyClockedNoWakeup<Spi>, Error<Spi::Error, Infallible>> {
|
||||
let mut adc = Max116xx10Bit::max11619(spi)?;
|
||||
adc.reset(false)?;
|
||||
adc.setup()?;
|
||||
Ok(adc)
|
||||
}
|
||||
|
||||
pub fn max11619_externally_clocked_with_wakeup<Spi: SpiDevice>(
|
||||
spi: Spi,
|
||||
) -> Result<Max11619ExternallyClockedWithWakeup<Spi>, Error<Spi::Error, Infallible>> {
|
||||
let mut adc = Max116xx10Bit::max11619(spi)?.into_ext_clkd_with_int_ref_wakeup_delay();
|
||||
adc.reset(false)?;
|
||||
adc.setup()?;
|
||||
Ok(adc)
|
||||
}
|
||||
|
||||
pub fn max11619_internally_clocked<Spi: SpiDevice>(
|
||||
spi: Spi,
|
||||
eoc: EocPin,
|
||||
v_ref: VoltageRefMode,
|
||||
) -> Result<Max11619InternallyClocked<Spi, EocPin>, 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)?;
|
||||
adc.setup()?;
|
||||
Ok(adc)
|
||||
}
|
79
vorago-reb1/src/temp_sensor.rs
Normal file
79
vorago-reb1/src/temp_sensor.rs
Normal file
@ -0,0 +1,79 @@
|
||||
//! # API for the On-Board Analog Devices ADT75 temperature sensor
|
||||
//!
|
||||
//! [Datasheet](https://www.analog.com/media/en/technical-documentation/data-sheets/ADT75.pdf)
|
||||
//!
|
||||
//! ## Examples
|
||||
//!
|
||||
//! - [Temperature Sensor example](https://egit.irs.uni-stuttgart.de/rust/vorago-reb1/src/branch/main/examples/adt75-temp-sensor.rs)
|
||||
use embedded_hal::i2c::{I2c, SevenBitAddress};
|
||||
use va108xx_hal::{
|
||||
i2c::{Error, I2cMaster, I2cSpeed, MasterConfig},
|
||||
pac,
|
||||
time::Hertz,
|
||||
};
|
||||
|
||||
const ADT75_I2C_ADDR: u8 = 0b1001000;
|
||||
|
||||
pub struct Adt75TempSensor {
|
||||
sensor_if: I2cMaster<pac::I2ca, SevenBitAddress>,
|
||||
cmd_buf: [u8; 1],
|
||||
current_reg: RegAddresses,
|
||||
}
|
||||
|
||||
#[derive(PartialEq, Eq, Debug, Copy, Clone)]
|
||||
pub enum RegAddresses {
|
||||
Temperature = 0x00,
|
||||
Configuration = 0x01,
|
||||
THystSetpoint = 0x02,
|
||||
TOsSetPoint = 0x03,
|
||||
OneShot = 0x04,
|
||||
}
|
||||
|
||||
impl Adt75TempSensor {
|
||||
pub fn new(
|
||||
i2ca: pac::I2ca,
|
||||
sys_clk: impl Into<Hertz> + Copy,
|
||||
sys_cfg: Option<&mut pac::Sysconfig>,
|
||||
) -> Result<Self, Error> {
|
||||
let mut sensor = Adt75TempSensor {
|
||||
sensor_if: I2cMaster::i2ca(
|
||||
i2ca,
|
||||
MasterConfig::default(),
|
||||
sys_clk,
|
||||
I2cSpeed::Regular100khz,
|
||||
sys_cfg,
|
||||
),
|
||||
cmd_buf: [RegAddresses::Temperature as u8],
|
||||
current_reg: RegAddresses::Temperature,
|
||||
};
|
||||
sensor.select_reg(RegAddresses::Temperature)?;
|
||||
Ok(sensor)
|
||||
}
|
||||
|
||||
pub fn select_reg(&mut self, reg: RegAddresses) -> Result<(), Error> {
|
||||
if reg != self.current_reg {
|
||||
self.cmd_buf[0] = reg as u8;
|
||||
self.current_reg = reg;
|
||||
self.sensor_if.write(ADT75_I2C_ADDR, &self.cmd_buf[0..1])?;
|
||||
}
|
||||
Ok(())
|
||||
}
|
||||
|
||||
pub fn read_temperature(&mut self) -> Result<f32, Error> {
|
||||
if self.current_reg != RegAddresses::Temperature {
|
||||
self.select_reg(RegAddresses::Temperature)?;
|
||||
}
|
||||
let mut reply: [u8; 2] = [0; 2];
|
||||
self.sensor_if.read(ADT75_I2C_ADDR, &mut reply)?;
|
||||
let adc_code = (((reply[0] as u16) << 8) | reply[1] as u16) >> 4;
|
||||
let temp_celcius: f32 = if ((adc_code >> 11) & 0x01) == 0 {
|
||||
// Sign bit not set, positiv value
|
||||
// Divide ADC code by 16 according to datasheet
|
||||
adc_code as f32 / 16.0
|
||||
} else {
|
||||
// Calculation for negative values, assuming all 12 bits are used
|
||||
(adc_code - 4096) as f32 / 16.0
|
||||
};
|
||||
Ok(temp_celcius)
|
||||
}
|
||||
}
|
Reference in New Issue
Block a user