Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 13 additions & 4 deletions examples/accel_pwm.rs
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ use stm32f3_discovery::compass::Compass;
use stm32f3_discovery::stm32f3xx_hal;
use stm32f3xx_hal::delay::Delay;
use stm32f3xx_hal::pwm::tim1;
use stm32f3xx_hal::{prelude::*, pac};
use stm32f3xx_hal::{pac, prelude::*};

#[entry]
fn main() -> ! {
Expand All @@ -35,9 +35,18 @@ fn main() -> ! {
// Prep the pins we need in their correct alternate function
let mut gpioe = device_periphs.GPIOE.split(&mut reset_and_clock_control.ahb);

let led_blue = gpioe.pe8.into_af2_push_pull(&mut gpioe.moder, &mut gpioe.otyper, &mut gpioe.afrh);
let led_green = gpioe.pe11.into_af2_push_pull(&mut gpioe.moder, &mut gpioe.otyper, &mut gpioe.afrh);
let lef_red = gpioe.pe13.into_af2_push_pull(&mut gpioe.moder, &mut gpioe.otyper, &mut gpioe.afrh);
let led_blue =
gpioe
.pe8
.into_af2_push_pull(&mut gpioe.moder, &mut gpioe.otyper, &mut gpioe.afrh);
let led_green =
gpioe
.pe11
.into_af2_push_pull(&mut gpioe.moder, &mut gpioe.otyper, &mut gpioe.afrh);
let lef_red =
gpioe
.pe13
.into_af2_push_pull(&mut gpioe.moder, &mut gpioe.otyper, &mut gpioe.afrh);

let max_duty = 4096;

Expand Down
2 changes: 1 addition & 1 deletion examples/blinky.rs
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@ extern crate panic_itm;
use cortex_m_rt::entry;

use stm32f3_discovery::stm32f3xx_hal::delay::Delay;
use stm32f3_discovery::stm32f3xx_hal::prelude::*;
use stm32f3_discovery::stm32f3xx_hal::pac;
use stm32f3_discovery::stm32f3xx_hal::prelude::*;

use stm32f3_discovery::leds::Leds;
use stm32f3_discovery::switch_hal::{OutputSwitch, ToggleableOutputSwitch};
Expand Down
15 changes: 8 additions & 7 deletions examples/blinky_int.rs
Original file line number Diff line number Diff line change
Expand Up @@ -10,17 +10,16 @@ use cortex_m::interrupt::{free, Mutex};

use cortex_m_rt::entry;

use stm32f3xx_hal::pac;
use stm32f3xx_hal::prelude::*;
use stm32f3xx_hal::timer::{Event, Timer};
use stm32f3xx_hal::pac;

use pac::{interrupt, Interrupt};

use switch_hal::{ToggleableOutputSwitch, IntoSwitch};
use switch_hal::{IntoSwitch, ToggleableOutputSwitch};

use stm32f3_discovery::wait_for_interrupt;


static TIM: Mutex<RefCell<Option<Timer<pac::TIM7>>>> = Mutex::new(RefCell::new(None));

#[interrupt]
Expand All @@ -46,13 +45,15 @@ fn main() -> ! {
});

let mut gpio = peripherals.GPIOE.split(&mut rcc.ahb);
let pin = gpio.pe9.into_push_pull_output(&mut gpio.moder, &mut gpio.otyper);
let pin = gpio
.pe9
.into_push_pull_output(&mut gpio.moder, &mut gpio.otyper);
let mut led = pin.into_active_high_switch();

unsafe {
pac::NVIC::unmask(Interrupt::TIM7);
}
pac::NVIC::unmask(Interrupt::TIM7);
}

loop {
led.toggle().ok();
wait_for_interrupt();
Expand Down
2 changes: 1 addition & 1 deletion examples/button.rs
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@ extern crate panic_itm;
use cortex_m_rt::entry;

use stm32f3_discovery::stm32f3xx_hal::delay::Delay;
use stm32f3_discovery::stm32f3xx_hal::prelude::*;
use stm32f3_discovery::stm32f3xx_hal::pac;
use stm32f3_discovery::stm32f3xx_hal::prelude::*;

use stm32f3_discovery::button::UserButton;
use stm32f3_discovery::leds::Leds;
Expand Down
2 changes: 1 addition & 1 deletion examples/button_int.rs
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@ extern crate panic_itm;
use cortex_m_rt::entry;

use stm32f3_discovery::stm32f3xx_hal::interrupt;
use stm32f3_discovery::stm32f3xx_hal::prelude::*;
use stm32f3_discovery::stm32f3xx_hal::pac;
use stm32f3_discovery::stm32f3xx_hal::prelude::*;
use stm32f3_discovery::wait_for_interrupt;

use core::sync::atomic::{AtomicBool, Ordering};
Expand Down
2 changes: 1 addition & 1 deletion examples/compass.rs
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,8 @@ use cortex_m_rt::{entry, exception};

use accelerometer::{Accelerometer, RawAccelerometer};
use stm32f3_discovery::compass::Compass;
use stm32f3_discovery::stm32f3xx_hal::prelude::*;
use stm32f3_discovery::stm32f3xx_hal::pac;
use stm32f3_discovery::stm32f3xx_hal::prelude::*;
use stm32f3_discovery::wait_for_interrupt;

#[entry]
Expand Down
2 changes: 1 addition & 1 deletion examples/leds.rs
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@ extern crate panic_itm;
use cortex_m_rt::entry;

use stm32f3_discovery::stm32f3xx_hal::delay::Delay;
use stm32f3_discovery::stm32f3xx_hal::prelude::*;
use stm32f3_discovery::stm32f3xx_hal::pac;
use stm32f3_discovery::stm32f3xx_hal::prelude::*;

use stm32f3_discovery::leds::Leds;
use stm32f3_discovery::switch_hal::OutputSwitch;
Expand Down
6 changes: 3 additions & 3 deletions examples/leds_directions.rs
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,14 @@ extern crate panic_itm;
use cortex_m_rt::entry;

use stm32f3_discovery::stm32f3xx_hal::delay::Delay;
use stm32f3_discovery::stm32f3xx_hal::prelude::*;
use stm32f3_discovery::stm32f3xx_hal::pac;
use stm32f3_discovery::stm32f3xx_hal::prelude::*;

use stm32f3xx_hal::gpio::gpioe;
use stm32f3xx_hal::gpio::{Output, PushPull};

use stm32f3_discovery::leds::{Direction, Leds};
use stm32f3_discovery::switch_hal::{Switch, ActiveHigh, OutputSwitch};
use stm32f3_discovery::switch_hal::{ActiveHigh, OutputSwitch, Switch};

#[entry]
fn main() -> ! {
Expand Down Expand Up @@ -44,7 +44,7 @@ fn main() -> ! {
let fast_delay = 50u16;
for direction in Direction::iter() {
let led = &mut leds.for_direction(*direction);

led.on().ok();
delay.delay_ms(fast_delay);
led.off().ok();
Expand Down
4 changes: 2 additions & 2 deletions examples/leds_iterator_test.rs
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@ extern crate panic_itm;
use cortex_m_rt::entry;

use stm32f3_discovery::stm32f3xx_hal::delay::Delay;
use stm32f3_discovery::stm32f3xx_hal::prelude::*;
use stm32f3_discovery::stm32f3xx_hal::pac;
use stm32f3_discovery::stm32f3xx_hal::prelude::*;

use stm32f3_discovery::leds::Leds;
use stm32f3_discovery::switch_hal::OutputSwitch;
Expand Down Expand Up @@ -71,7 +71,7 @@ fn main() -> ! {
// we're in the middle, so panic if either of the next two calls returns a led
iter.next().map(|_| panic!("Got a Some!"));
iter.next_back().map(|_| panic!("Got a Some!"));

// turn everything back off
for led in &mut leds {
led.off().ok();
Expand Down
7 changes: 5 additions & 2 deletions src/button/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
pub mod interrupt;

use stm32f3xx_hal::gpio::gpioa::PA0;
use stm32f3xx_hal::gpio::{Input, gpioa};
use stm32f3xx_hal::gpio::{gpioa, Input};
use switch_hal::{ActiveHigh, InputSwitch, IntoSwitch, Switch};

/// Wrapper struct around `ActiveHighButton<PA0<Input>>`
Expand All @@ -16,7 +16,10 @@ impl UserButton {
pub fn new(pa0: PA0<Input>, moder: &mut gpioa::MODER, pupdr: &mut gpioa::PUPDR) -> Self {
// This button is equipped with an external pull-down and so there is
// no need to use the internal one.
UserButton(pa0.into_floating_input(moder, pupdr).into_active_high_switch())
UserButton(
pa0.into_floating_input(moder, pupdr)
.into_active_high_switch(),
)
}
}

Expand Down
26 changes: 16 additions & 10 deletions src/compass.rs
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,15 @@ use stm32f3xx_hal::pac;
use stm32f3xx_hal::prelude::*;
use stm32f3xx_hal::rcc;


type Lsm303 =
lsm303dlhc::Lsm303dlhc<i2c::I2c<pac::I2C1, (gpiob::PB6<gpio::AF4<OpenDrain>>, gpiob::PB7<gpio::AF4<OpenDrain>>)>>;
type Lsm303 = lsm303dlhc::Lsm303dlhc<
i2c::I2c<
pac::I2C1,
(
gpiob::PB6<gpio::AF4<OpenDrain>>,
gpiob::PB7<gpio::AF4<OpenDrain>>,
),
>,
>;

pub struct Compass {
lsm303dlhc: Lsm303,
Expand Down Expand Up @@ -69,31 +75,31 @@ impl RawAccelerometer<I16x3> for Compass {
}

/// Reads Accelerometer data in G-Force
///
///
/// # Warning
/// This is hard coded for the default settings because the driver doesn't provide a way
/// to read the necessary registers to calculate it based on current settings.
/// If you take control of the underlying device driver and change settings,
/// this will not calculate the correct G-Force values.
impl Accelerometer for Compass {
type Error = i2c::Error;
fn accel_norm(&mut self) -> Result<F32x3, accelerometer::Error<Self::Error>> {
fn accel_norm(&mut self) -> Result<F32x3, accelerometer::Error<Self::Error>> {
let reading = self.accel_raw()?;
/*
* LA_FS (linear acceleration measurment range [full scale])
* can be +/-2, +/-4, +/-8, or +/- 16
* can be +/-2, +/-4, +/-8, or +/- 16
* LA_So (Linear acceleration sensitivity) can be 1,2,4, or 12
* and is measured in milli-G / LSB
* The driver provides a way to set the range/sensitivy,
* but no way to read it, so we just hard code the default settings here (for now?).
*
* At +/-2g, we get 1mg/LSB (1 mg/bit) resolution.
* The device returns a 16 bit result.
* magnitude g / (1 mg / bit) =
* magnitude g / (1 mg / bit) =
* +/- 2g range = 4g magnitude
* 4g / 65535 bits = 4g/(1<<16) = 0.000061 g / bit
* 2g / 32768 bits = 2g/(1<<15) = 0.000061 g / bit
*
*
* I _think_ the general equation is:
* scale_factor = magnitude / #of_bits * sensitivity
* scale_factor = (abs(range)*2) / #of_bits * sensitivity
Expand All @@ -109,14 +115,14 @@ impl Accelerometer for Compass {
const NO_OF_BITS: i32 = 1 << 16;
const SENSITIVITY: i32 = 1;
const SCALE_FACTOR: f32 = (MAGNITUDE as f32 / NO_OF_BITS as f32) * SENSITIVITY as f32;
Ok(F32x3::new (
Ok(F32x3::new(
reading.x as f32 * SCALE_FACTOR,
reading.y as f32 * SCALE_FACTOR,
reading.z as f32 * SCALE_FACTOR,
))
}

fn sample_rate(&mut self) -> Result<f32, accelerometer::Error<<Self as Accelerometer>::Error>> {
fn sample_rate(&mut self) -> Result<f32, accelerometer::Error<<Self as Accelerometer>::Error>> {
// we don't expose a way to change this, so hard coded to 400Hz right now
// it should really be read from the device in case someone snags the raw lsm303dlhc struct,
// but the driver does't give us a way to read it back from the device
Expand Down
Loading