diff --git a/Cargo.toml b/Cargo.toml index e053f0b..bf8c1db 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -21,31 +21,34 @@ repository = "https://github.com/stm32-rs/stm32l1xx-hal" version = "0.1.0" [dependencies] -cortex-m = "0.5.8" -nb = "0.1.1" -stm32l1 = "0.5.0" +cortex-m = "0.7.1" +nb = "1.0.0" +stm32l1 = "0.14.0" +bare-metal = "1.0.0" -[dependencies.bare-metal] -features = ["const-fn"] -version = "0.2.4" +[dependencies.stm32-usbd] +version = "0.6.0" +optional = true [dependencies.cast] default-features = false -version = "0.2.2" +version = "0.3.0" [dependencies.embedded-hal] features = ["unproven"] -version = "0.2.3" +version = "0.2.6" [dependencies.void] default-features = false version = "1.0.2" [dev-dependencies] -cortex-m-rt = "0.6.7" -cortex-m-semihosting = "0.3.2" -panic-semihosting = "0.5.1" -cortex-m-rtic = "0.5.5" +cortex-m-rt = "0.7.1" +cortex-m-semihosting = "0.3.7" +panic-semihosting = "0.5.6" +cortex-m-rtic = "1.0.0" +usb-device = "0.2.8" +usbd-serial = "0.1.1" [features] rt = ["stm32l1/rt"] @@ -70,3 +73,7 @@ required-features = ["rt"] [[example]] name = "timer" required-features = ["rt"] + +[[example]] +name = "usb_serial" +required-features = ["rt", "stm32-usbd"] diff --git a/examples/button_irq.rs b/examples/button_irq.rs index d7e9720..3878e0b 100644 --- a/examples/button_irq.rs +++ b/examples/button_irq.rs @@ -23,9 +23,11 @@ static INT: Mutex>> = Mutex::new(RefCell::new(None)); #[entry] fn main() -> ! { let dp = stm32::Peripherals::take().unwrap(); - let mut cp = cortex_m::Peripherals::take().unwrap(); - cp.NVIC.enable(Interrupt::EXTI0); + unsafe { + cortex_m::peripheral::NVIC::unmask(Interrupt::EXTI0); + } + dp.EXTI.listen(0, TriggerEdge::Falling); cortex_m::interrupt::free(move |cs| { diff --git a/examples/rtfm.rs b/examples/rtfm.rs index 2ce6b06..290bac9 100644 --- a/examples/rtfm.rs +++ b/examples/rtfm.rs @@ -9,35 +9,34 @@ extern crate panic_semihosting; extern crate rtic; extern crate stm32l1xx_hal as hal; -use cortex_m_semihosting::hprintln; -use rtic::app; +#[rtic::app(device = hal::stm32, peripherals = true)] +mod app { + use cortex_m_semihosting::hprintln; + use embedded_hal::digital::v2::OutputPin; + use embedded_hal::digital::v2::ToggleableOutputPin; + use hal::exti::TriggerEdge; + use hal::gpio::gpiob::{PB6, PB7}; + use hal::gpio::{Output, PushPull}; + use hal::prelude::*; + use hal::rcc::Config; + use hal::stm32; + use hal::timer::Timer; -use embedded_hal::digital::v2::OutputPin; -use embedded_hal::digital::v2::ToggleableOutputPin; -use hal::exti::TriggerEdge; -use hal::gpio::gpiob::{PB6, PB7}; -use hal::gpio::{Output, PushPull}; -use hal::prelude::*; -use hal::rcc::Config; -use hal::stm32; -use hal::timer::Timer; - -#[app(device = hal::stm32, peripherals = true)] -const APP: () = { - struct Resources { - // resources - #[init(0)] - DELTA: u32, + #[shared] + struct Shared { + delta: u32, + } - // late resources - TIMER: Timer, - TICKS_LED: PB6>, - BUSY_LED: PB7>, - EXTI: stm32::EXTI, + #[local] + struct Local { + timer: Timer, + ticks_led: PB6>, + busy_led: PB7>, + exti: stm32::EXTI, } #[init] - fn init(cx: init::Context) -> init::LateResources { + fn init(cx: init::Context) -> (Shared, Local, init::Monotonics) { let mut rcc = cx.device.RCC.freeze(Config::hsi()); let gpiob = cx.device.GPIOB.split(); @@ -46,39 +45,38 @@ const APP: () = { timer.listen(); cx.device.EXTI.listen(0, TriggerEdge::Rising); - let TICKS_LED = gpiob.pb6.into_push_pull_output(); - let BUSY_LED = gpiob.pb7.into_push_pull_output(); - let TIMER = timer; - let EXTI = cx.device.EXTI; + let ticks_led = gpiob.pb6.into_push_pull_output(); + let busy_led = gpiob.pb7.into_push_pull_output(); + let timer = timer; + let exti = cx.device.EXTI; - init::LateResources { - TIMER, - TICKS_LED, - BUSY_LED, - EXTI, - } + ( + Shared { delta: 0 }, + Local { + timer, + ticks_led, + busy_led, + exti, + }, + init::Monotonics(), + ) } - #[task(binds = TIM2, resources = [TIMER, TICKS_LED, DELTA])] - fn tim2_handler(cx: tim2_handler::Context) { - *cx.resources.DELTA += 1; + #[task(binds = TIM2, shared = [delta], local = [timer, ticks_led])] + fn tim2_handler(mut cx: tim2_handler::Context) { + cx.shared.delta.lock(|d| *d += 1); - cx.resources.TICKS_LED.toggle().unwrap(); - cx.resources.TIMER.clear_irq(); + cx.local.ticks_led.toggle().unwrap(); + cx.local.timer.clear_irq(); } - #[task(binds = EXTI0, resources = [EXTI, BUSY_LED, DELTA])] - fn exti0_handler(cx: exti0_handler::Context) { - cx.resources.BUSY_LED.set_high().unwrap(); - hprintln!("Δ: {}", cx.resources.DELTA).unwrap(); - cx.resources.BUSY_LED.set_low().unwrap(); - - *cx.resources.DELTA = 0; - cx.resources.EXTI.clear_irq(0); - } + #[task(binds = EXTI0, shared = [delta], local = [exti, busy_led])] + fn exti0_handler(mut cx: exti0_handler::Context) { + cx.local.busy_led.set_high().unwrap(); + hprintln!("Δ: {}", cx.shared.delta.lock(|d| *d)).unwrap(); + cx.local.busy_led.set_low().unwrap(); - #[idle] - fn idle(_: idle::Context) -> ! { - loop {} + cx.shared.delta.lock(|d| *d = 0); + cx.local.exti.clear_irq(0); } -}; +} diff --git a/examples/timer.rs b/examples/timer.rs index 84cdb0e..192b879 100644 --- a/examples/timer.rs +++ b/examples/timer.rs @@ -23,13 +23,14 @@ static TIMER: Mutex>>> = Mutex::new(RefCell::n #[entry] fn main() -> ! { let dp = stm32::Peripherals::take().unwrap(); - let mut cp = cortex_m::Peripherals::take().unwrap(); let mut rcc = dp.RCC.freeze(Config::hsi()); let mut timer = dp.TIM2.timer(1.hz(), &mut rcc); timer.listen(); - cp.NVIC.enable(Interrupt::TIM2); + unsafe { + cortex_m::peripheral::NVIC::unmask(Interrupt::TIM2); + } cortex_m::interrupt::free(move |cs| { *TIMER.borrow(cs).borrow_mut() = Some(timer); diff --git a/examples/usb_serial.rs b/examples/usb_serial.rs new file mode 100644 index 0000000..e8c629f --- /dev/null +++ b/examples/usb_serial.rs @@ -0,0 +1,106 @@ +//! CDC-ACM serial port example using polling in a busy loop. +//! +//! Note: +//! When building this since this is a larger program, +//! one would need to build it using release profile +//! since debug profiles generates artifacts that +//! cause FLASH overflow errors due to their size +#![no_std] +#![no_main] + +extern crate cortex_m; +extern crate cortex_m_rt as rt; +extern crate panic_semihosting; +extern crate stm32l1xx_hal as hal; + +use embedded_hal::digital::v2::OutputPin; +use hal::prelude::*; +use hal::rcc::{Config, PLLDiv, PLLMul, PLLSource}; +use hal::stm32; +use hal::usb::{Peripheral, UsbBus}; +use rt::entry; +use usb_device::prelude::*; +use usbd_serial::{SerialPort, USB_CLASS_CDC}; + +#[entry] +fn main() -> ! { + let dp = stm32::Peripherals::take().unwrap(); + let cp = cortex_m::Peripherals::take().unwrap(); + + // dp.RCC.apb1enr.modify(|_, w| w.pwren().set_bit()); + // dp.PWR.cr.write(|w| unsafe { w.vos().bits(1) }); + // while dp.PWR.csr.read().vosf().bit_is_set() {} + + dp.FLASH.acr.write(|w| w.acc64().set_bit()); + dp.FLASH.acr.modify(|_, w| w.prften().set_bit()); + dp.FLASH.acr.modify(|_, w| w.latency().set_bit()); + + let mut rcc = dp.RCC.freeze(Config::pll( + PLLSource::HSE(16.mhz()), + PLLMul::Mul6, + PLLDiv::Div4, + )); + let mut delay = cp.SYST.delay(rcc.clocks); + + let mut gpioa = dp.GPIOA.split(); + + let mut led = gpioa.pa1.into_push_pull_output(); + led.set_low().unwrap(); + + // Pull the D+ pin down to send a RESET condition to the USB bus. + // This forced reset is needed only for development, without it host + // will not reset your device when you upload new firmware. + let mut usb_dp = gpioa.pa12.into_push_pull_output(); + usb_dp.set_low().unwrap(); + delay.delay(10.ms()); + + let usb = Peripheral { + usb: dp.USB, + pin_dm: gpioa.pa11, + pin_dp: usb_dp.into_floating_input(), + }; + let usb_bus = UsbBus::new(usb); + + let mut serial = SerialPort::new(&usb_bus); + + let mut usb_dev = UsbDeviceBuilder::new(&usb_bus, UsbVidPid(0x16c0, 0x27dd)) + .manufacturer("stm32-rs") + .product("Serial port") + .serial_number("TEST") + .device_class(USB_CLASS_CDC) + .build(); + + loop { + if !usb_dev.poll(&mut [&mut serial]) { + continue; + } + + let mut buf = [0u8; 64]; + + match serial.read(&mut buf) { + Ok(count) if count > 0 => { + led.set_high().unwrap(); + + // Echo back in upper case + for c in buf[0..count].iter_mut() { + if 0x61 <= *c && *c <= 0x7a { + *c &= !0x20; + } + } + + let mut write_offset = 0; + while write_offset < count { + match serial.write(&buf[write_offset..count]) { + Ok(len) if len > 0 => { + write_offset += len; + } + _ => {} + } + } + } + _ => {} + } + + led.set_low().unwrap(); + } +} diff --git a/memory.x b/memory.x index 5641c8d..7fb2625 100644 --- a/memory.x +++ b/memory.x @@ -1,6 +1,6 @@ -/* Linker script for the STM32L152RCT6 */ +/* Linker script for the STM32L151C8 */ MEMORY { - FLASH : ORIGIN = 0x08000000, LENGTH = 256K - RAM : ORIGIN = 0x20000000, LENGTH = 32K + FLASH : ORIGIN = 0x08000000, LENGTH = 128K + RAM : ORIGIN = 0x20000000, LENGTH = 16K } diff --git a/src/gpio.rs b/src/gpio.rs index 2eb721c..5f14571 100644 --- a/src/gpio.rs +++ b/src/gpio.rs @@ -178,12 +178,12 @@ macro_rules! gpio { ) -> $PXi> { let offset = 2 * $i; unsafe { - &(*$GPIOX::ptr()).pupdr.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).pupdr.modify(|r, w| { w.bits((r.bits() & !(0b11 << offset)) | (0b00 << offset)) }); - &(*$GPIOX::ptr()).moder.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).moder.modify(|r, w| { w.bits((r.bits() & !(0b11 << offset)) | (0b00 << offset)) - }) + }); }; $PXi { _mode: PhantomData } } @@ -194,12 +194,12 @@ macro_rules! gpio { ) -> $PXi> { let offset = 2 * $i; unsafe { - &(*$GPIOX::ptr()).pupdr.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).pupdr.modify(|r, w| { w.bits((r.bits() & !(0b11 << offset)) | (0b10 << offset)) }); - &(*$GPIOX::ptr()).moder.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).moder.modify(|r, w| { w.bits((r.bits() & !(0b11 << offset)) | (0b00 << offset)) - }) + }); }; $PXi { _mode: PhantomData } } @@ -210,12 +210,12 @@ macro_rules! gpio { ) -> $PXi> { let offset = 2 * $i; unsafe { - &(*$GPIOX::ptr()).pupdr.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).pupdr.modify(|r, w| { w.bits((r.bits() & !(0b11 << offset)) | (0b01 << offset)) }); - &(*$GPIOX::ptr()).moder.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).moder.modify(|r, w| { w.bits((r.bits() & !(0b11 << offset)) | (0b00 << offset)) - }) + }); }; $PXi { _mode: PhantomData } } @@ -226,10 +226,10 @@ macro_rules! gpio { ) -> $PXi { let offset = 2 * $i; unsafe { - &(*$GPIOX::ptr()).pupdr.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).pupdr.modify(|r, w| { w.bits((r.bits() & !(0b11 << offset)) | (0b00 << offset)) }); - &(*$GPIOX::ptr()).moder.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).moder.modify(|r, w| { w.bits((r.bits() & !(0b11 << offset)) | (0b11 << offset)) }); } @@ -242,15 +242,15 @@ macro_rules! gpio { ) -> $PXi> { let offset = 2 * $i; unsafe { - &(*$GPIOX::ptr()).pupdr.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).pupdr.modify(|r, w| { w.bits((r.bits() & !(0b11 << offset)) | (0b00 << offset)) }); - &(*$GPIOX::ptr()).otyper.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).otyper.modify(|r, w| { w.bits(r.bits() | (0b1 << $i)) }); - &(*$GPIOX::ptr()).moder.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).moder.modify(|r, w| { w.bits((r.bits() & !(0b11 << offset)) | (0b01 << offset)) - }) + }); }; $PXi { _mode: PhantomData } } @@ -261,15 +261,15 @@ macro_rules! gpio { ) -> $PXi> { let offset = 2 * $i; unsafe { - &(*$GPIOX::ptr()).pupdr.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).pupdr.modify(|r, w| { w.bits((r.bits() & !(0b11 << offset)) | (0b00 << offset)) }); - &(*$GPIOX::ptr()).otyper.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).otyper.modify(|r, w| { w.bits(r.bits() & !(0b1 << $i)) }); - &(*$GPIOX::ptr()).moder.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).moder.modify(|r, w| { w.bits((r.bits() & !(0b11 << offset)) | (0b01 << offset)) - }) + }); }; $PXi { _mode: PhantomData } } @@ -292,16 +292,16 @@ macro_rules! gpio { let offset2 = 4 * $i; unsafe { if offset2 < 32 { - &(*$GPIOX::ptr()).afrl.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).afrl.modify(|r, w| { w.bits((r.bits() & !(0b1111 << offset2)) | (mode << offset2)) }); } else { let offset2 = offset2 - 32; - &(*$GPIOX::ptr()).afrh.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).afrh.modify(|r, w| { w.bits((r.bits() & !(0b1111 << offset2)) | (mode << offset2)) }); } - &(*$GPIOX::ptr()).moder.modify(|r, w| { + let _ = &(*$GPIOX::ptr()).moder.modify(|r, w| { w.bits((r.bits() & !(0b11 << offset)) | (0b10 << offset)) }); } diff --git a/src/i2c.rs b/src/i2c.rs index 5dca3c3..b795338 100644 --- a/src/i2c.rs +++ b/src/i2c.rs @@ -7,11 +7,14 @@ use crate::prelude::*; use crate::rcc::Rcc; use crate::stm32::{I2C1, I2C2}; use crate::time::Hertz; +use cortex_m::peripheral::DWT; /// I2C abstraction pub struct I2c { i2c: I2C, pins: PINS, + speed: Hertz, + clock: u32, } pub trait Pins { @@ -39,10 +42,56 @@ impl Pins for (PB10>, PB11>) { } } -#[derive(Debug)] +#[derive(Debug, PartialEq)] pub enum Error { - OVERRUN, - NACK, + Bus, + Arbitration, + Acknowledge, + Overrun, + Timeout, +} + +macro_rules! wait_for_flag { + ($i2c:expr, $flag:ident) => {{ + let sr1 = $i2c.sr1.read(); + + if sr1.berr().bit_is_set() { + $i2c.sr1.write(|w| w.berr().clear_bit()); + Err(Error::Bus) + } else if sr1.arlo().bit_is_set() { + $i2c.sr1.write(|w| w.arlo().clear_bit()); + Err(Error::Arbitration) + } else if sr1.af().bit_is_set() { + $i2c.sr1.write(|w| w.af().clear_bit()); + Err(Error::Acknowledge) + } else if sr1.ovr().bit_is_set() { + $i2c.sr1.write(|w| w.ovr().clear_bit()); + Err(Error::Overrun) + } else { + Ok(sr1.$flag().bit_is_set()) + } + }}; +} + +macro_rules! busy_wait { + ($nb_expr:expr, $exit_cond:expr) => {{ + loop { + match $nb_expr { + Err(e) => break Err(e), + Ok(true) => break Ok(()), + Ok(false) if $exit_cond => break Err(Error::Timeout), + Ok(false) => {} + } + } + }}; +} + +macro_rules! busy_wait_cycles { + ($nb_expr:expr, $cycles:expr) => {{ + let started = DWT::cycle_count(); + let cycles = $cycles; + busy_wait!($nb_expr, DWT::cycle_count().wrapping_sub(started) >= cycles) + }}; } macro_rules! i2c { @@ -62,14 +111,30 @@ macro_rules! i2c { rcc.rb.apb1rstr.modify(|_, w| w.$i2crst().set_bit()); rcc.rb.apb1rstr.modify(|_, w| w.$i2crst().clear_bit()); - // Make sure the I2C unit is disabled so we can configure it - i2c.cr1.modify(|_, w| w.pe().clear_bit()); - // Calculate settings for I2C speed modes let clock = rcc.clocks.apb1_clk().0; let freq = clock / 1_000_000; assert!(freq >= 2 && freq <= 50); + let mut i2c = I2c { + i2c, + pins, + speed, + clock, + }; + i2c.init(); + i2c + } + + fn init(&mut self) { + let i2c = &mut self.i2c; + let speed = self.speed; + let clock = self.clock; + let freq = clock / 1_000_000; + + // Make sure the I2C unit is disabled so we can configure it + i2c.cr1.modify(|_, w| w.pe().clear_bit()); + // Configure bus frequency into I2C peripheral i2c.cr2.write(|w| unsafe { w.freq().bits(freq as u8) }); @@ -125,29 +190,46 @@ macro_rules! i2c { // Enable the I2C processing i2c.cr1.modify(|_, w| w.pe().set_bit()); - - I2c { i2c, pins } } pub fn release(self) -> ($I2CX, PINS) { (self.i2c, self.pins) } - fn write_bytes(&mut self, addr: u8, bytes: &[u8]) -> Result<(), Error> { - // Send a START condition - self.i2c.cr1.modify(|_, w| w.start().set_bit()); + fn send_start(&mut self) -> Result<(), Error> { + let mut retries_left = 10; + let mut last_err = Err(Error::Timeout); + while retries_left > 0 { + // Send a START condition + self.i2c.cr1.modify(|_, w| w.start().set_bit()); + + // Wait until START condition was generated + last_err = busy_wait_cycles!(wait_for_flag!(self.i2c, sb), 24_0000); + + if last_err.is_err() { + self.i2c.cr1.write(|w| w.pe().set_bit().swrst().set_bit()); + self.i2c.cr1.reset(); + self.init(); + } else { + break; + } + + retries_left -= 1; + } + last_err + } - // Wait until START condition was generated - while { - let sr1 = self.i2c.sr1.read(); - sr1.sb().bit_is_clear() - } {} + fn write_bytes(&mut self, addr: u8, bytes: &[u8]) -> Result<(), Error> { + self.send_start()?; // Also wait until signalled we're master and everything is waiting for us - while { - let sr2 = self.i2c.sr2.read(); - sr2.msl().bit_is_clear() && sr2.busy().bit_is_clear() - } {} + busy_wait_cycles!( + { + let sr2 = self.i2c.sr2.read(); + Ok(sr2.msl().bit_is_set() && sr2.busy().bit_is_set()) + }, + 24_0000 + )?; // Set up current address, we're trying to talk to self.i2c @@ -155,10 +237,7 @@ macro_rules! i2c { .write(|w| unsafe { w.bits(u32::from(addr) << 1) }); // Wait until address was sent - while { - let sr1 = self.i2c.sr1.read(); - sr1.addr().bit_is_clear() - } {} + busy_wait_cycles!(wait_for_flag!(self.i2c, addr), 24_0000)?; // Clear condition by reading SR2 self.i2c.sr2.read(); @@ -174,28 +253,19 @@ macro_rules! i2c { fn send_byte(&self, byte: u8) -> Result<(), Error> { // Wait until we're ready for sending - while self.i2c.sr1.read().tx_e().bit_is_clear() {} + busy_wait_cycles!(wait_for_flag!(self.i2c, tx_e), 24_0000)?; // Push out a byte of data self.i2c.dr.write(|w| unsafe { w.bits(u32::from(byte)) }); - // While until byte is transferred - while { - let sr1 = self.i2c.sr1.read(); - - // If we received a NACK, then this is an error - if sr1.af().bit_is_set() { - return Err(Error::NACK); - } - - sr1.btf().bit_is_clear() - } {} + // Wait until byte is transferred + busy_wait_cycles!(wait_for_flag!(self.i2c, btf), 24_0000)?; Ok(()) } fn recv_byte(&self) -> Result { - while self.i2c.sr1.read().rx_ne().bit_is_clear() {} + busy_wait_cycles!(wait_for_flag!(self.i2c, rx_ne), 24_0000)?; let value = self.i2c.dr.read().bits() as u8; Ok(value) } @@ -243,22 +313,16 @@ macro_rules! i2c { fn read(&mut self, addr: u8, buffer: &mut [u8]) -> Result<(), Self::Error> { if let Some((last, buffer)) = buffer.split_last_mut() { - // Send a START condition and set ACK bit - self.i2c - .cr1 - .modify(|_, w| w.start().set_bit().ack().set_bit()); - - // Wait until START condition was generated - while { - let sr1 = self.i2c.sr1.read(); - sr1.sb().bit_is_clear() - } {} + self.send_start()?; // Also wait until signalled we're master and everything is waiting for us - while { - let sr2 = self.i2c.sr2.read(); - sr2.msl().bit_is_clear() && sr2.busy().bit_is_clear() - } {} + busy_wait_cycles!( + { + let sr2 = self.i2c.sr2.read(); + Ok(sr2.msl().bit_is_set() && sr2.busy().bit_is_set()) + }, + 24_0000 + )?; // Set up current address, we're trying to talk to self.i2c @@ -266,10 +330,7 @@ macro_rules! i2c { .write(|w| unsafe { w.bits((u32::from(addr) << 1) + 1) }); // Wait until address was sent - while { - let sr1 = self.i2c.sr1.read(); - sr1.addr().bit_is_clear() - } {} + busy_wait_cycles!(wait_for_flag!(self.i2c, addr), 24_0000)?; // Clear condition by reading SR2 self.i2c.sr2.read(); @@ -290,7 +351,7 @@ macro_rules! i2c { // Fallthrough is success Ok(()) } else { - Err(Error::OVERRUN) + Err(Error::Overrun) } } } diff --git a/src/lib.rs b/src/lib.rs index d7b1920..e908756 100755 --- a/src/lib.rs +++ b/src/lib.rs @@ -49,4 +49,6 @@ pub mod serial; pub mod spi; pub mod time; pub mod timer; +#[cfg(feature = "stm32-usbd")] +pub mod usb; pub mod watchdog; diff --git a/src/pwm.rs b/src/pwm.rs index b2a14ef..9cacbcf 100644 --- a/src/pwm.rs +++ b/src/pwm.rs @@ -54,14 +54,14 @@ macro_rules! channels { fn enable(&mut self) { unsafe { let tim = &*$TIMX::ptr(); - tim.ccmr1_output + tim.ccmr1_output() .modify(|_, w| w.oc1pe().set_bit().oc1m().bits(6)); tim.ccer.modify(|_, w| w.cc1e().set_bit()); } } fn get_duty(&self) -> u16 { - unsafe { (*$TIMX::ptr()).ccr1.read().ccr1().bits() } + unsafe { (*$TIMX::ptr()).ccr1.read().ccr().bits() } } fn get_max_duty(&self) -> u16 { @@ -69,7 +69,7 @@ macro_rules! channels { } fn set_duty(&mut self, duty: u16) { - unsafe { (*$TIMX::ptr()).ccr1.write(|w| w.ccr1().bits(duty)) } + unsafe { (*$TIMX::ptr()).ccr1.write(|w| w.ccr().bits(duty)) } } } }; @@ -137,14 +137,14 @@ macro_rules! channels { fn enable(&mut self) { unsafe { let tim = &*$TIMX::ptr(); - tim.ccmr1_output + tim.ccmr1_output() .modify(|_, w| w.oc2pe().set_bit().oc2m().bits(6)); tim.ccer.modify(|_, w| w.cc2e().set_bit()); } } fn get_duty(&self) -> u16 { - unsafe { (*$TIMX::ptr()).ccr2.read().ccr2().bits() } + unsafe { (*$TIMX::ptr()).ccr2.read().ccr().bits() } } fn get_max_duty(&self) -> u16 { @@ -152,7 +152,7 @@ macro_rules! channels { } fn set_duty(&mut self, duty: u16) { - unsafe { (*$TIMX::ptr()).ccr2.write(|w| w.ccr2().bits(duty)) } + unsafe { (*$TIMX::ptr()).ccr2.write(|w| w.ccr().bits(duty)) } } } @@ -168,14 +168,14 @@ macro_rules! channels { fn enable(&mut self) { unsafe { let tim = &*$TIMX::ptr(); - tim.ccmr2_output + tim.ccmr2_output() .modify(|_, w| w.oc3pe().set_bit().oc3m().bits(6)); tim.ccer.modify(|_, w| w.cc3e().set_bit()); } } fn get_duty(&self) -> u16 { - unsafe { (*$TIMX::ptr()).ccr3.read().ccr3().bits() } + unsafe { (*$TIMX::ptr()).ccr3.read().ccr().bits() } } fn get_max_duty(&self) -> u16 { @@ -183,7 +183,7 @@ macro_rules! channels { } fn set_duty(&mut self, duty: u16) { - unsafe { (*$TIMX::ptr()).ccr3.write(|w| w.ccr3().bits(duty)) } + unsafe { (*$TIMX::ptr()).ccr3.write(|w| w.ccr().bits(duty)) } } } @@ -199,14 +199,14 @@ macro_rules! channels { fn enable(&mut self) { unsafe { let tim = &*$TIMX::ptr(); - tim.ccmr2_output + tim.ccmr2_output() .modify(|_, w| w.oc4pe().set_bit().oc4m().bits(6)); tim.ccer.modify(|_, w| w.cc4e().set_bit()); } } fn get_duty(&self) -> u16 { - unsafe { (*$TIMX::ptr()).ccr4.read().ccr4().bits() } + unsafe { (*$TIMX::ptr()).ccr4.read().ccr().bits() } } fn get_max_duty(&self) -> u16 { @@ -214,7 +214,7 @@ macro_rules! channels { } fn set_duty(&mut self, duty: u16) { - unsafe { (*$TIMX::ptr()).ccr4.write(|w| w.ccr4().bits(duty)) } + unsafe { (*$TIMX::ptr()).ccr4.write(|w| w.ccr().bits(duty)) } } } }; @@ -257,7 +257,7 @@ macro_rules! timers { let ticks = clk / freq; let psc = u16((ticks - 1) / (1 << 16)).unwrap(); let arr = u16(ticks / u32(psc + 1)).unwrap(); - tim.psc.write(|w| unsafe { w.psc().bits(psc) }); + tim.psc.write(|w| w.psc().bits(psc) ); #[allow(unused_unsafe)] tim.arr.write(|w| unsafe { w.arr().bits(arr) }); tim.cr1.write(|w| w.cen().set_bit()); diff --git a/src/qei.rs b/src/qei.rs index edb4544..d702859 100644 --- a/src/qei.rs +++ b/src/qei.rs @@ -63,7 +63,7 @@ macro_rules! hal { rcc.rb.apb1rstr.modify(|_, w| w.$timXrst().clear_bit()); // Configure TxC1 and TxC2 as captures - tim.ccmr1_output.write(|w| unsafe { + tim.ccmr1_output().write(|w| unsafe { w.cc1s().bits(0b01).cc2s().set_bit() }); @@ -84,7 +84,7 @@ macro_rules! hal { }); // Encoder mode, count up/down on both TI1FP1 and TI2FP2 - tim.smcr.write(|w| unsafe { w.sms().bits(0b011) }); + tim.smcr.write(|w| w.sms().bits(0b011) ); tim.arr.write(|w| w.arr().bits(u16::MAX)); tim.cr1.write(|w| w.cen().enabled()); diff --git a/src/rcc.rs b/src/rcc.rs index e19c6be..43827f3 100644 --- a/src/rcc.rs +++ b/src/rcc.rs @@ -220,7 +220,7 @@ impl RccExt for RCC { }; // Disable PLL - self.cr.write(|w| w.pllon().clear_bit()); + self.cr.modify(|_, w| w.pllon().clear_bit()); while self.cr.read().pllrdy().bit_is_set() {} let mul_bytes = mul as u8; @@ -243,9 +243,9 @@ impl RccExt for RCC { PLLDiv::Div3 => freq / 3, PLLDiv::Div4 => freq / 4, }; - assert!(freq <= 24.mhz().0); + assert!(freq <= 32.mhz().0); - self.cfgr.write(move |w| unsafe { + self.cfgr.modify(move |_, w| unsafe { w.pllmul() .bits(mul_bytes) .plldiv() @@ -255,7 +255,7 @@ impl RccExt for RCC { }); // Enable PLL - self.cr.write(|w| w.pllon().set_bit()); + self.cr.modify(|_, w| w.pllon().set_bit()); while self.cr.read().pllrdy().bit_is_clear() {} (freq, 3) diff --git a/src/time.rs b/src/time.rs index 56962e1..ca9ea02 100644 --- a/src/time.rs +++ b/src/time.rs @@ -108,7 +108,7 @@ impl MonoTimer { /// Returns an `Instant` corresponding to "now" pub fn now(&self) -> Instant { Instant { - now: DWT::get_cycle_count(), + now: DWT::cycle_count(), } } } @@ -131,6 +131,6 @@ pub struct Instant { impl Instant { /// Ticks elapsed since the `Instant` was created pub fn elapsed(&self) -> u32 { - DWT::get_cycle_count().wrapping_sub(self.now) + DWT::cycle_count().wrapping_sub(self.now) } } diff --git a/src/timer.rs b/src/timer.rs index 7d0f944..e57181d 100644 --- a/src/timer.rs +++ b/src/timer.rs @@ -151,7 +151,7 @@ macro_rules! timers { let ticks = self.clocks.$timclk().0 / freq; let psc = u16((ticks - 1) / (1 << 16)).unwrap(); - self.tim.psc.write(|w| unsafe { w.psc().bits(psc) }); + self.tim.psc.write(|w| w.psc().bits(psc) ); self.tim.arr.write(|w| unsafe { w.bits(ticks / u32(psc + 1)) }); self.tim.cr1.modify(|_, w| w.urs().set_bit()); diff --git a/src/usb.rs b/src/usb.rs new file mode 100644 index 0000000..ec597ae --- /dev/null +++ b/src/usb.rs @@ -0,0 +1,51 @@ +//! USB peripheral +//! +//! Requires the `stm32-usbd` feature. +//! See https://github.com/stm32-rs/stm32l1xx-hal/tree/master/examples +//! for usage examples. + +use crate::stm32::{RCC, USB}; +use stm32_usbd::UsbPeripheral; + +use crate::gpio::gpioa::{PA11, PA12}; +use crate::gpio::{Floating, Input}; +pub use stm32_usbd::UsbBus; + +pub struct Peripheral { + pub usb: USB, + pub pin_dm: PA11>, + pub pin_dp: PA12>, +} + +unsafe impl Sync for Peripheral {} + +unsafe impl UsbPeripheral for Peripheral { + const REGISTERS: *const () = USB::ptr() as *const (); + const DP_PULL_UP_FEATURE: bool = true; + const EP_MEMORY: *const () = 0x4000_6000 as _; + const EP_MEMORY_SIZE: usize = 512; + const EP_MEMORY_ACCESS_2X16: bool = false; + + fn enable() { + unsafe { + let rcc = &*RCC::ptr(); + + cortex_m::interrupt::free(|_| { + // Enable USB peripheral + rcc.apb1enr.modify(|_, w| w.usben().set_bit()); + + // Reset USB peripheral + rcc.apb1rstr.modify(|_, w| w.usbrst().set_bit()); + rcc.apb1rstr.modify(|_, w| w.usbrst().clear_bit()); + }); + } + } + + fn startup_delay() { + // There is a chip specific startup delay. For STM32L15x it's 1µs and this should wait for + // at least that long. + cortex_m::asm::delay(72); + } +} + +pub type UsbBusType = UsbBus;