diff --git a/examples/spi_stm32f4/Cargo.toml b/examples/spi_stm32f4/Cargo.toml new file mode 100644 index 00000000..def84634 --- /dev/null +++ b/examples/spi_stm32f4/Cargo.toml @@ -0,0 +1,12 @@ +[package] +name = "spi_stm32f4" +version = "0.0.1" + +[features] +default = ["mcu_stm32f4"] +mcu_stm32f4 = ["zinc/mcu_stm32f4"] + +[dependencies] +zinc = { path = "../.." } +macro_zinc = { path = "../../macro_zinc" } +core = { git = "https://github.com/hackndev/rust-libcore" } diff --git a/examples/spi_stm32f4/src/main.rs b/examples/spi_stm32f4/src/main.rs new file mode 100644 index 00000000..2091d652 --- /dev/null +++ b/examples/spi_stm32f4/src/main.rs @@ -0,0 +1,82 @@ +#![feature(core_intrinsics)] +#![feature(plugin, no_std)] +#![no_std] +#![plugin(macro_zinc)] + + +extern crate zinc; + +use zinc::hal::timer::Timer; +use zinc::hal::pin::Gpio; +use zinc::hal::stm32f4::{pin, timer, spi}; +use zinc::hal::spi::Spi; +use core::intrinsics::abort; + +#[zinc_main] +pub fn main() { + zinc::hal::mem_init::init_stack(); + zinc::hal::mem_init::init_data(); + + let led1 = pin::Pin::new ( + pin::Port::PortD, + 13u8, + pin::Mode::GpioOut(pin::OutputType::OutPushPull, pin::Speed::VeryLow), + pin::PullType::PullNone + ); + + let spi1Sck = pin::Pin::new ( + pin::Port::PortA, + 5u8, + pin::Mode::AltFunction(pin::AltMode::AfSpi1_Spi2, pin::OutputType::OutPushPull, pin::Speed::High), + pin::PullType::PullNone + ); + + let spi1Miso = pin::Pin::new ( + pin::Port::PortA, + 6u8, + pin::Mode::AltFunction(pin::AltMode::AfSpi1_Spi2, pin::OutputType::OutPushPull, pin::Speed::High), + pin::PullType::PullNone + ); + + let spi1Mosi = pin::Pin::new ( + pin::Port::PortA, + 7u8, + pin::Mode::AltFunction(pin::AltMode::AfSpi1_Spi2, pin::OutputType::OutPushPull, pin::Speed::High), + pin::PullType::PullNone + ); + + let spi1Ss = pin::Pin::new( + pin::Port::PortA, + 4u8, + pin::Mode::GpioOut(pin::OutputType::OutPushPull, pin::Speed::VeryLow), + pin::PullType::PullNone + ); + + let timer = timer::Timer::new(timer::TimerPeripheral::Timer2, 25u32); + + let spi1 = match spi::Spi::new( + spi::Peripheral::Spi1, + spi::Direction::FullDuplex, + spi::Role::Master, + spi::DataSize::U8, + spi::DataFormat::MsbFirst, + 6) { + Ok(e) => e, + _ => unsafe {abort ()}, + }; + + spi1Ss.set_high(); + + loop { + led1.set_high(); + spi1Ss.set_low(); + spi1.write('H' as u8); + spi1.write('e' as u8); + spi1.write('l' as u8); + spi1.write('l' as u8); + spi1.write('o' as u8); + spi1.write('!' as u8); + //led1.set_low(); + //spi1Ss.set_high(); + } +} diff --git a/src/hal/layout_common.ld b/src/hal/layout_common.ld index 5ab161e8..ac269261 100644 --- a/src/hal/layout_common.ld +++ b/src/hal/layout_common.ld @@ -2,6 +2,8 @@ __aeabi_unwind_cpp_pr0 = abort; __aeabi_unwind_cpp_pr1 = abort; __aeabi_unwind_cpp_pr2 = abort; +__exidx_start = abort; +__exidx_end = abort; __aeabi_memclr4 = __aeabi_memclr; @@ -60,6 +62,6 @@ SECTIONS *(.rel.*) /* dynamic relocations */ *(.ARM.exidx*) /* index entries for section unwinding */ *(.ARM.extab*) /* exception unwinding information */ - *(.debug_gdb_scripts) + /**(.debug_gdb_scripts)*/ } } diff --git a/src/hal/stm32f4/iomem.ld b/src/hal/stm32f4/iomem.ld index fd9313e4..1e4af01f 100644 --- a/src/hal/stm32f4/iomem.ld +++ b/src/hal/stm32f4/iomem.ld @@ -14,3 +14,10 @@ stm32f4_iomem_GPIOF = 0x40021400; stm32f4_iomem_GPIOG = 0x40021800; stm32f4_iomem_GPIOH = 0x40021c00; stm32f4_iomem_GPIOI = 0x40022000; + +stm32f4_iomem_SPI1 = 0x40013000; +stm32f4_iomem_SPI2 = 0x40003800; +stm32f4_iomem_SPI3 = 0x40003C00; +stm32f4_iomem_SPI4 = 0x40013400; +stm32f4_iomem_SPI5 = 0x40015000; +stm32f4_iomem_SPI6 = 0x40015400; diff --git a/src/hal/stm32f4/mod.rs b/src/hal/stm32f4/mod.rs index f945cedc..e980af57 100644 --- a/src/hal/stm32f4/mod.rs +++ b/src/hal/stm32f4/mod.rs @@ -19,3 +19,5 @@ pub mod init; pub mod peripheral_clock; pub mod pin; pub mod timer; +#[allow(missing_docs)] +pub mod spi; diff --git a/src/hal/stm32f4/peripheral_clock.rs b/src/hal/stm32f4/peripheral_clock.rs index 0802ea2f..8146685e 100644 --- a/src/hal/stm32f4/peripheral_clock.rs +++ b/src/hal/stm32f4/peripheral_clock.rs @@ -219,7 +219,7 @@ impl PeripheralClock { SDIOClock|SPI1Clock|SYSCFGClock|TIM9Clock|TIM10Clock| TIM11Clock => { let val = reg::RCC.APB2ENR(); - reg::RCC.set_AHB1ENR((val & mask) | bit); + reg::RCC.set_APB2ENR((val & mask) | bit); }, } diff --git a/src/hal/stm32f4/pin.rs b/src/hal/stm32f4/pin.rs index 07d9572d..0fda0ec4 100644 --- a/src/hal/stm32f4/pin.rs +++ b/src/hal/stm32f4/pin.rs @@ -1,5 +1,5 @@ // Zinc, the bare metal stack for rust. -// Copyright 2014 Vladimir "farcaller" Pouzanov +// Copyright 2014 Dzmitry "kvark" Malyshau // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -13,22 +13,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -//! Pin configuration for ST STM32F4. +//! Pin configuration for ST STM32L1. //! //! Some pins that could be configured here may be missing from actual MCU //! depending on the package. -use hal::pin::{Gpio, GpioDirection, GpioLevel}; use super::peripheral_clock; use core::intrinsics::abort; - use self::Port::*; -#[path="../../util/ioreg.rs"] -#[macro_use] mod ioreg; - /// Available port names. #[allow(missing_docs)] +#[repr(u8)] #[derive(Clone, Copy)] pub enum Port { PortA, @@ -39,200 +35,232 @@ pub enum Port { PortF, PortG, PortH, - PortI, + PortI } -/// Pin functions. +/// Pin output type. #[allow(missing_docs)] +#[repr(u8)] #[derive(Clone, Copy)] -pub enum Function { - GPIOIn = 0, - GPIOOut = 1, - AltFunction = 2, - Analog = 3, +pub enum OutputType { + OutPushPull = 0, + OutOpenDrain = 1, } -impl Port { - fn clock(self) -> peripheral_clock::PeripheralClock { - use hal::stm32f4::peripheral_clock::PeripheralClock::*; - match self { - PortA => GPIOAClock, - PortB => GPIOBClock, - PortC => GPIOCClock, - PortD => GPIODClock, - PortE => GPIOEClock, - PortF => GPIOFClock, - PortG => GPIOGClock, - PortH => GPIOHClock, - PortI => GPIOIClock, - } - } +/// Pin pull resistors: up, down, or none. +#[allow(missing_docs)] +#[repr(u8)] +#[derive(Clone, Copy)] +pub enum PullType { + PullNone = 0, + PullUp = 1, + PullDown = 2, +} + +/// Pin speed. +#[repr(u8)] +#[derive(Clone, Copy)] +pub enum Speed { + /// 400 KHz + VeryLow = 0, + /// 2 MHz + Low = 1, + /// 10 MHz + Medium = 2, + /// 40 MHz + High = 3, } -/// Pin configuration +/// Extended pin modes. +#[allow(missing_docs, non_camel_case_types)] +#[repr(u8)] +#[derive(Clone, Copy)] +pub enum AltMode { + AfRtc50Mhz_Mco_RtcAfl_Wakeup_SwJtag_Trace = 0, + AfTim2 = 1, + AfTim3_Tim4_Tim5 = 2, + AfTim9_Tim10_Tim11 = 3, + AfI2C1_I2C2 = 4, + AfSpi1_Spi2 = 5, + AfSpi3 = 6, + AfUsart1_Usart2_Usart3 = 7, + AfUart4_Uart5 = 8, + AfUsb = 10, + AfLcd = 11, + AfFsmc_Sdio = 12, + AfRe = 14, + AfEventOut = 15, +} + +/// Pin mode. +#[derive(Clone, Copy)] +pub enum Mode { + /// GPIO Input Mode + GpioIn, + /// GPIO Output Mode + GpioOut(OutputType, Speed), + /// GPIO Alternate function Mode + AltFunction(AltMode, OutputType, Speed), + /// GPIO Analog Mode + Analog, +} + +/// Pin configuration. #[derive(Clone, Copy)] pub struct Pin { - /// Pin port, mcu-specific. - pub port: Port, - /// Pin number. - pub pin: u8, - /// Pin function, mcu-specific. - pub function: Function, + /// Pin index. + pub index: u8, + /// GPIO register + reg: &'static reg::GPIO, } impl Pin { /// Setup the pin. #[inline(always)] - pub fn setup(&self) { - use self::Function::*; - use self::reg::GPIO_moder_mode as RegMode; - - self.port.clock().enable(); // TODO(farcaller): should be done once per port + pub fn new(port: Port, pin_index: u8, mode: Mode, pull_type: PullType) -> Pin { + use hal::stm32f4::peripheral_clock::PeripheralClock as clock; + use self::Mode::*; + let (reg, clock) = match port { + PortA => (®::GPIOA, clock::GPIOAClock), + PortB => (®::GPIOB, clock::GPIOBClock), + PortC => (®::GPIOC, clock::GPIOCClock), + PortD => (®::GPIOD, clock::GPIODClock), + PortE => (®::GPIOE, clock::GPIOEClock), + PortF => (®::GPIOF, clock::GPIOFClock), + PortG => (®::GPIOG, clock::GPIOGClock), + PortH => (®::GPIOH, clock::GPIOHClock), + PortI => (®::GPIOI, clock::GPIOIClock), + }; + // TODO(farcaller): should be done once per port + clock.enable(); - let offset = self.pin as usize; - let gpreg = self.get_reg(); + let offset1 = pin_index as usize; + let mask1 = !(0b1u16 << offset1); + let offset2 = pin_index as usize * 2; + let mask2: u32 = !(0b11 << offset2); - let val = match self.function { - GPIOOut => RegMode::Output, - GPIOIn => RegMode::Input, - _ => unsafe { abort() }, // FIXME(farcaller): not implemented + let fun: u32 = match mode { + GpioIn => 0b00, + GpioOut(otype, speed) => { + // set type and speed + let tv: u16 = reg.otyper.otype() & mask1; + reg.otyper.set_otype(tv | ((otype as u16) << offset1)); + let sv: u32 = reg.ospeedr.speed() & mask2; + reg.ospeedr.set_speed(sv | ((speed as u32) << offset2)); + // done + 0b01 + }, + AltFunction(alt, otype, speed) => { + // set type and speed + let tv: u16 = reg.otyper.otype() & mask1; + reg.otyper.set_otype(tv | ((otype as u16) << offset1)); + let sv: u32 = reg.ospeedr.speed() & mask2; + reg.ospeedr.set_speed(sv | ((speed as u32) << offset2)); + // set alt mode + let mut off = (pin_index as usize) << 2; + if pin_index < 8 { + let v = reg.afrl.alt_fun() & !(0xF << off); + reg.afrl.set_alt_fun(v | ((alt as u32) << off)); + }else { + off -= 32; + let v = reg.afrh.alt_fun() & !(0xF << off); + reg.afrh.set_alt_fun(v | ((alt as u32) << off)); + } + // done + 0b10 + }, + Analog => { + //unsafe { abort() } //TODO + 0b11 + }, }; - gpreg.moder.set_mode(offset, val); - } - - /// Toggles the GPIO value - pub fn toggle(&self) { - let reg = self.get_reg(); - let offset = self.pin as usize; + let mode: u32 = reg.moder.mode() & mask2; + reg.moder.set_mode(mode | (fun << offset2)); - reg.odr.set_od(offset, !reg.odr.od(offset)); - } + let pull: u32 = reg.pupdr.mode() & mask2; + let pull_val = (pull_type as u32) << offset2; + reg.pupdr.set_mode(pull | pull_val); - fn get_reg(&self) -> ®::GPIO { - match self.port { - PortA => ®::GPIO_A, - PortB => ®::GPIO_B, - PortC => ®::GPIO_C, - PortD => ®::GPIO_D, - PortE => ®::GPIO_E, - PortF => ®::GPIO_F, - PortG => ®::GPIO_G, - PortH => ®::GPIO_H, - PortI => ®::GPIO_I, + Pin { + index: pin_index, + reg: reg, } } } -impl Gpio for Pin { - /// Sets output GPIO value to high. +impl ::hal::pin::Gpio for Pin { fn set_high(&self) { - let offset = self.pin as usize; - self.get_reg().bsrr.set_bs(offset, true); + let bit: u32 = 1 << self.index as usize; + self.reg.bsrr.set_reset(bit); } - /// Sets output GPIO value to low. fn set_low(&self) { - let offset = self.pin as usize; - self.get_reg().bsrr.set_br(offset, true); + let bit: u32 = 1 << (self.index as usize + 16); + self.reg.bsrr.set_reset(bit); } - /// Returns input GPIO level. - fn level(&self) -> GpioLevel { - let offset = self.pin as usize; - let reg = self.get_reg(); + fn level(&self) -> ::hal::pin::GpioLevel { + let bit = 1u16 << (self.index as usize); - match reg.idr.id(offset) { - false => GpioLevel::Low, - _ => GpioLevel::High, + match self.reg.idr.input() & bit { + 0 => ::hal::pin::Low, + _ => ::hal::pin::High, } } - /// Sets output GPIO direction. - fn set_direction(&self, new_mode: GpioDirection) { - // TODO(darayus): Verify that this works - // TODO(darayus): Change the Pin.function field to the new mode - use self::reg::GPIO_moder_mode as RegMode; - let offset = self.pin as usize; - let reg = self.get_reg(); - - let val = match new_mode { - GpioDirection::Out => RegMode::Output, - GpioDirection::In => RegMode::Input, - }; - - reg.moder.set_mode(offset, val); + fn set_direction(&self, _new_mode: ::hal::pin::GpioDirection) { + //TODO(kvark) + unsafe { abort() } } } -#[allow(dead_code)] mod reg { - use core::ops::Drop; use volatile_cell::VolatileCell; + use core::ops::Drop; ioregs!(GPIO = { - 0x0 => reg32 moder { - 0..31 => mode[16] { - 0 => Input, - 1 => Output, - 3 => Alternate, - 4 => Analog - } - } - 0x04 => reg32 otyper { - 0..15 => ot[16] { - 0 => PushPull, - 1 => OpenDrain - } - } - 0x08 => reg32 ospeedr { - 0..31 => ospeed[16] { - 0 => Low, - 1 => Medium, - 2 => Fast, - 3 => High - } - } - 0x0c => reg32 pupdr { - 0..31 => pupd[16] { - 0 => None, - 1 => PullUp, - 2 => PullDown - } - } - 0x10 => reg32 idr { - 0..15 => id[16]: ro - } - 0x14 => reg32 odr { - 0..15 => od[16] - } - 0x18 => reg32 bsrr { - 0..15 => bs[16]: wo, - 16..31 => br[16]: wo - } - 0x1c => reg32 lckr { - 0..15 => lck[16], - 16 => lckk - } - 0x20 => reg32 afrl { - 0..31 => afrl[8] - } - 0x24 => reg32 afrh { - 0..31 => afrh[8] + 0x00 => reg32 moder { // port mode + 31..0 => mode : rw, + }, + 0x04 => reg16 otyper { // port output type + 15..0 => otype : rw, + }, + 0x08 => reg32 ospeedr { // port output speed + 31..0 => speed : rw, + }, + 0x0C => reg32 pupdr { // port pull-up/pull-down + 31..0 => mode : rw, + }, + 0x10 => reg16 idr { // port input data + 15..0 => input : rw, + }, + 0x14 => reg16 odr { // port output data + 15..0 => output : rw, + }, + 0x18 => reg32 bsrr { // port bit set/reset + 31..0 => reset : rw, + }, + 0x1C => reg32 lckr { // port configuration lock + 31..0 => config_lock : rw, + }, + 0x20 => reg32 afrl { // alternate function low + 31..0 => alt_fun : rw, + }, + 0x24 => reg32 afrh { // alternate function high + 31..0 => alt_fun : rw, } }); extern { - #[link_name="stm32f4_iomem_GPIOA"] pub static GPIO_A: GPIO; - #[link_name="stm32f4_iomem_GPIOB"] pub static GPIO_B: GPIO; - #[link_name="stm32f4_iomem_GPIOC"] pub static GPIO_C: GPIO; - #[link_name="stm32f4_iomem_GPIOD"] pub static GPIO_D: GPIO; - #[link_name="stm32f4_iomem_GPIOE"] pub static GPIO_E: GPIO; - #[link_name="stm32f4_iomem_GPIOF"] pub static GPIO_F: GPIO; - #[link_name="stm32f4_iomem_GPIOG"] pub static GPIO_G: GPIO; - #[link_name="stm32f4_iomem_GPIOH"] pub static GPIO_H: GPIO; - #[link_name="stm32f4_iomem_GPIOI"] pub static GPIO_I: GPIO; - // define_reg!(GPIO_J: GPIO @ 0x40022400) - // define_reg!(GPIO_K: GPIO @ 0x40022800) + #[link_name="stm32f4_iomem_GPIOA"] pub static GPIOA: GPIO; + #[link_name="stm32f4_iomem_GPIOB"] pub static GPIOB: GPIO; + #[link_name="stm32f4_iomem_GPIOC"] pub static GPIOC: GPIO; + #[link_name="stm32f4_iomem_GPIOD"] pub static GPIOD: GPIO; + #[link_name="stm32f4_iomem_GPIOE"] pub static GPIOE: GPIO; + #[link_name="stm32f4_iomem_GPIOF"] pub static GPIOF: GPIO; + #[link_name="stm32f4_iomem_GPIOG"] pub static GPIOG: GPIO; + #[link_name="stm32f4_iomem_GPIOH"] pub static GPIOH: GPIO; + #[link_name="stm32f4_iomem_GPIOH"] pub static GPIOI: GPIO; } } diff --git a/src/hal/stm32f4/spi.rs b/src/hal/stm32f4/spi.rs new file mode 100644 index 00000000..34b7155c --- /dev/null +++ b/src/hal/stm32f4/spi.rs @@ -0,0 +1,292 @@ +// Zinc, the bare metal stack for rust. +// Copyright 2014 Dzmitry "kvark" Malyshau +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +//! Serial Peripheral Interface for STM32L1. + +use core::result::Result; +use core::result::Result::{Ok, Err}; +use core::marker::Copy; + +#[path="../../util/wait_for.rs"] +#[macro_use] mod wait_for; + +/// Available SPI peripherals. +#[allow(missing_docs)] +#[repr(u8)] +#[derive(Clone, Copy)] +pub enum Peripheral { + Spi1, + Spi2, + Spi3, + Spi4, + Spi5, + Spi6 +} + +/// SPI direction modes. +#[repr(u8)] +#[derive(PartialEq, Clone, Copy)] +pub enum Direction { + /// 2 lines, default mode + FullDuplex, + /// 2 lines, but read-only + RxOnly, + /// 1 line, read + Rx, + /// 1 line, transmit + Tx, +} + +#[allow(missing_docs)] +#[repr(u8)] +#[derive(Clone)] +pub enum Role { + Slave = 0, + Master = 1, +} + +impl Copy for Role {} + +#[allow(missing_docs)] +#[repr(u8)] +#[derive(Clone, Copy)] +pub enum DataSize { + U8 = 0, + U16 = 1, +} + +/// SPI data format. +#[repr(u8)] +#[derive(Clone, Copy)] +pub enum DataFormat { + /// Most Significant Bit + MsbFirst = 0, + /// Least Significant Bit + LsbFirst = 1, +} + +#[allow(missing_docs)] +#[repr(u8)] +#[derive(Clone, Copy)] +pub enum ClockPhase { + Edge1 = 0, + Edge2 = 1, +} + +#[allow(missing_docs)] +#[repr(u8)] +#[derive(Clone, Copy)] +pub enum ClockPolarity { + Low = 0, + High = 1, +} + +/// SPI initialization errors. +#[repr(u8)] +#[derive(Clone, Copy)] +pub enum Error { + /// Invalid baud rate shift. + BaudRate, + /// Invalid resulting mode. + Mode, +} + +/// Structure describing a SPI instance. +#[derive(Clone, Copy)] +pub struct Spi { + reg: &'static reg::SPI, +} + +impl Spi { + /// Create a new SPI port. + pub fn new(peripheral: Peripheral, direction: Direction, + role: Role, data_size: DataSize, format: DataFormat, + prescaler_shift: u8) -> Result { + use hal::stm32f4::peripheral_clock::PeripheralClock; + + let (reg, clock) = match peripheral { + Peripheral::Spi1 => (®::SPI1, PeripheralClock::SPI1Clock), + Peripheral::Spi2 => (®::SPI2, PeripheralClock::SPI2Clock), + Peripheral::Spi3 => (®::SPI3, PeripheralClock::SPI3Clock), + Peripheral::Spi4 => (®::SPI4, PeripheralClock::SPI1Clock), + Peripheral::Spi5 => (®::SPI5, PeripheralClock::SPI2Clock), + Peripheral::Spi6 => (®::SPI6, PeripheralClock::SPI3Clock), + }; + + clock.enable(); + + // set direction + reg.cr1.set_receive_only(direction == Direction::RxOnly); + reg.cr1.set_bidirectional_data_mode(direction == Direction::Rx + || direction == Direction::Tx); + reg.cr1.set_bidirectional_output_enable(direction == Direction::Tx); + + // set role + reg.cr1.set_master(role as usize != 0); + reg.cr1.set_internal_slave_select(role as usize != 0); + reg.cr1.set_software_slave_management(true); + reg.cr2.set_ss_output_enable(false); + + // set data size and format (MSB or LSB) + reg.cr1.set_data_frame_format(data_size as usize != 0); + reg.cr1.set_frame_format(format as usize != 0); + + // set baud rate + if prescaler_shift<1 || prescaler_shift>8 { + return Err(Error::BaudRate) + } + reg.cr1.set_baud_rate(prescaler_shift as u16 - 1); + + // set clock mode + reg.cr1.set_clock_phase(ClockPhase::Edge1 as usize != 0); + reg.cr1.set_clock_polarity(ClockPolarity::Low as usize != 0); + + reg.i2s_cfgr.set_enable(false); + reg.cr1.set_hardware_crc_enable(false); + reg.crc.set_polynomial(0); //TODO + + if reg.sr.mode_fault() { + Err(Error::Mode) + }else { + reg.cr1.set_spi_enable(true); + Ok(Spi { + reg: reg, + }) + } + } + + /// Returns the status byte. + pub fn get_status(&self) -> u8 { + //self.reg.sr.raw() //TODO(kvark): #245 doesn't work + let mut r = 0u8; + if self.reg.sr.receive_buffer_not_empty() { + r |= 1u8<<0; + } + if self.reg.sr.transmit_buffer_empty() { + r |= 1u8<<1; + } + if self.reg.sr.channel_side() { + r |= 1u8<<2; + } + if self.reg.sr.underrun_flag() { + r |= 1u8<<3; + } + if self.reg.sr.crc_error() { + r |= 1u8<<4; + } + if self.reg.sr.mode_fault() { + r |= 1u8<<5; + } + if self.reg.sr.overrun_flag() { + r |= 1u8<<6; + } + if self.reg.sr.busy_flag() { + r |= 1u8<<7; + } + r + } +} + +impl ::hal::spi::Spi for Spi { + fn write(&self, value: u8) { + wait_for!(self.reg.sr.transmit_buffer_empty()); + self.reg.dr.set_data(value as u16); + } + + fn read(&self) -> u8 { + wait_for!(self.reg.sr.receive_buffer_not_empty()); + self.reg.dr.data() as u8 + } +} + +mod reg { + use volatile_cell::VolatileCell; + use core::ops::Drop; + + ioregs!(SPI = { + 0x00 => reg16 cr1 { // control 1 + 0 => clock_phase : rw, + 1 => clock_polarity : rw, + 2 => master : rw, + 5..3 => baud_rate : rw, + 6 => spi_enable : rw, + 7 => frame_format : rw, + 8 => internal_slave_select : rw, + 9 => software_slave_management : rw, + 10 => receive_only : rw, + 11 => data_frame_format : rw, + 12 => transmit_crc_next : rw, + 13 => hardware_crc_enable : rw, + 14 => bidirectional_output_enable : rw, + 15 => bidirectional_data_mode : rw, + }, + 0x04 => reg8 cr2 { // control 2 + 0 => rx_dma_enable : rw, + 1 => tx_dma_enable : rw, + 2 => ss_output_enable : rw, + 3 => frame_format : rw, + // 4 is reserved + 5 => error_interrupt_enable : rw, + 6 => rx_buffer_not_empty_interrupt_enable : rw, + 7 => tx_buffer_empty_interrupt_enable : rw, + }, + 0x08 => reg8 sr { // status + 0 => receive_buffer_not_empty : ro, + 1 => transmit_buffer_empty : ro, + 2 => channel_side : ro, + 3 => underrun_flag : ro, + 4 => crc_error : ro, + 5 => mode_fault : ro, + 6 => overrun_flag : ro, + 7 => busy_flag : ro, + }, + 0x0C => reg16 dr { // data + 15..0 => data : rw, + }, + 0x10 => reg16 crc { // CRC + 15..0 => polynomial : rw, + }, + 0x14 => reg16 rx_crc { // Rx CRC + 15..0 => crc : rw, + }, + 0x18 => reg16 tx_crc { // Tx CRC + 15..0 => crc : rw, + }, + 0x1C => reg16 i2s_cfgr { // I2S config + 0 => channel_length : rw, + 2..1 => data_length : rw, + 3 => clock_polarity : rw, + 5..4 => standard_selection : rw, + 7 => pcm_frame_sync : rw, + 9..8 => configuration_mode : rw, + 10 => enable : rw, + 11 => mode_selection : rw, + }, + 0x20 => reg16 i2s_pr { // I2S prescaler + 7..0 => linear_prescaler : rw, + 8 => odd_factor : rw, + 9 => master_clock_output_enable : rw, + }, + }); + + extern { + #[link_name="stm32f4_iomem_SPI1"] pub static SPI1: SPI; + #[link_name="stm32f4_iomem_SPI2"] pub static SPI2: SPI; + #[link_name="stm32f4_iomem_SPI3"] pub static SPI3: SPI; + #[link_name="stm32f4_iomem_SPI4"] pub static SPI4: SPI; + #[link_name="stm32f4_iomem_SPI5"] pub static SPI5: SPI; + #[link_name="stm32f4_iomem_SPI6"] pub static SPI6: SPI; + } +}