diff options
author | Brian Cully <bjc@kublai.com> | 2022-10-25 12:20:32 -0400 |
---|---|---|
committer | Brian Cully <bjc@kublai.com> | 2022-10-25 12:20:32 -0400 |
commit | 0c4eb964b015961e3c90e45ef498f6c7f89eddba (patch) | |
tree | b0cc3b540e7123b45da044c73d1f47f98ce010ef /src | |
parent | 0f80c612d59c855a99073e583db339fe6a42b883 (diff) | |
download | luchie-0c4eb964b015961e3c90e45ef498f6c7f89eddba.tar.gz luchie-0c4eb964b015961e3c90e45ef498f6c7f89eddba.zip |
convert to gd32f303 (stm32f103) bluepill variant
Diffstat (limited to 'src')
-rw-r--r-- | src/blink.rs | 67 | ||||
-rw-r--r-- | src/boot.S | 11 | ||||
-rw-r--r-- | src/led.rs | 24 | ||||
-rw-r--r-- | src/log.rs | 20 | ||||
-rwxr-xr-x | src/main.rs | 285 | ||||
-rwxr-xr-x | src/usb.rs | 42 |
6 files changed, 162 insertions, 287 deletions
diff --git a/src/blink.rs b/src/blink.rs deleted file mode 100644 index ba3d6ca..0000000 --- a/src/blink.rs +++ /dev/null @@ -1,67 +0,0 @@ -use core::convert::Infallible; - -use gd32vf103xx_hal::{ - eclic::{self, EclicExt}, - pac::{self, Interrupt}, - prelude::*, - time::Hertz, - timer::{Event, Timer}, -}; -use nb; -use riscv::interrupt; - -use crate::led::LED; - -pub struct Task { - timer: Timer<pac::TIMER6>, - frequency: Hertz, - led: LED, -} - -static mut TIMER_FIRED: bool = false; - -impl Task { - pub fn new(mut timer: Timer<pac::TIMER6>, frequency: Hertz, led: LED) -> Self { - pac::ECLIC::setup(Interrupt::TIMER6, eclic::TriggerType::RisingEdge, eclic::Level::L0, eclic::Priority::P3); - unsafe { pac::ECLIC::unmask(Interrupt::TIMER6); } - assert!(pac::ECLIC::is_enabled(Interrupt::TIMER6)); - timer.listen(Event::Update); - - Self { timer, frequency, led } - } - - pub fn poll(&mut self) -> nb::Result<(), Infallible> { - interrupt::free(|_cs| { - if unsafe { TIMER_FIRED } { - unsafe { TIMER_FIRED = false }; - self.led.toggle(); - self.timer.start(self.frequency); - } - }); - Err(nb::Error::WouldBlock) - } -} - -/* - * because i'm using ‘wfi’ to sleep as much as possible, i need to - * actually schedule the timer to fire an interrupt. that, in turn, - * requires a handler. - * - * why? because, for efficiency reasons, ‘_irq_handler’ uses the - * bumblebee core ‘jalmnxti’ csr, and the default entry in the irq - * vector is ‘0’. so the core jumps to 0, which is the ‘_start’ entry - * point. but it does this *from the interrupt*, which masks the - * interrupt (because it's currently being serviced), so any - * subsequent firings are never triggered, nor any interrupts at lower - * priority. - * - * so it looks like the core resets every other time it's - * started. adding a real isr avoids these problems. - */ -#[export_name="TIMER6"] -fn timer6() { - // logln!("I timer6 I"); - let regs = unsafe { &*pac::TIMER6::ptr() }; - regs.intf.write(|w| w.upif().clear_bit()); - unsafe { TIMER_FIRED = true }; -} diff --git a/src/boot.S b/src/boot.S deleted file mode 100644 index d31e5fe..0000000 --- a/src/boot.S +++ /dev/null @@ -1,11 +0,0 @@ - .global _start - .section .text.init -_start: - .option push - .option norelax - la gp, __global_pointer$ - .option pop - la sp, _stack_top - - csrr a0, mhartid - tail main @@ -1,17 +1,23 @@ -use gd32vf103xx_hal::{ - gpio::{Floating, Input, Output, PushPull, Pxx, State, gpioa::PA7}, +use stm32f1xx_hal::{ + gpio::{Cr, CRL, Floating, Input, Output, PushPull, gpiob::PB2}, }; -use embedded_hal::digital::v2::OutputPin; + +enum State { + Low, + High, +} + +type LEDPin<MODE> = PB2<MODE>; pub struct LED { - pin: Pxx<Output<PushPull>>, + pin: LEDPin<Output<PushPull>>, state: State, } impl LED { - pub fn new(pin: PA7<Input<Floating>>) -> Self { - let mut p = pin.into_push_pull_output().downgrade(); - p.set_low().ok(); + pub fn new(pin: LEDPin<Input<Floating>>, cr: &mut Cr<CRL, 'B'>) -> Self { + let mut p = pin.into_push_pull_output(cr); + p.set_low(); Self { pin: p, state: State::Low } } @@ -24,12 +30,12 @@ impl LED { pub fn on(&mut self) { self.state = State::High; - self.pin.set_high().ok(); + self.pin.set_high(); } pub fn off(&mut self) { self.state = State::Low; - self.pin.set_low().ok(); + self.pin.set_low(); } pub fn toggle(&mut self) { @@ -1,10 +1,14 @@ -use core::fmt::{write, Arguments}; +use core::{ + cell::RefCell, + fmt::{write, Arguments}, +}; -use gd32vf103xx_hal::{ +use stm32f1xx_hal::{ serial::Tx, pac::USART1, }; -use riscv::interrupt::{self, Mutex}; + +use cortex_m::interrupt::{self, Mutex}; #[macro_export] macro_rules! log { @@ -21,16 +25,16 @@ macro_rules! logln { } } -static mut TX: Mutex<Option<Tx<USART1>>> = Mutex::new(None); +static TX: Mutex<RefCell<Option<Tx<USART1>>>> = Mutex::new(RefCell::new(None)); pub fn init(tx: Tx<USART1>) { - interrupt::free(|_cs| { - unsafe { TX.get_mut().insert(tx) }; + interrupt::free(|cs| { + TX.borrow(cs).replace(Some(tx)); }); } pub fn log_args(args: Arguments) { - interrupt::free(|_cs| { - unsafe { TX.get_mut().as_mut().map(|tx| write(tx, args)) }; + interrupt::free(|cs| { + TX.borrow(cs).borrow_mut().as_mut().map(|tx| write(tx, args)); }); } diff --git a/src/main.rs b/src/main.rs index dce005a..d0dfe1a 100755 --- a/src/main.rs +++ b/src/main.rs @@ -1,191 +1,176 @@ -/* #![no_std] #![no_main] -mod blink; +//extern crate panic_semihosting; + mod led; mod log; -mod usb; - -use gd32vf103xx_hal::{ - afio::AfioExt, - eclic::{self, EclicExt}, - gpio::GpioExt, - pac::{self, Peripherals}, - rcu::RcuExt, - serial::Serial, - time::{Hertz, MegaHertz}, - timer::Timer, -}; -use riscv::{ - asm::wfi, - interrupt, -}; -use riscv_rt::entry; -use usb_device::prelude::*; use led::LED; -use usb::{USB, UsbBus}; -static mut EP_MEMORY: [u32; 1024] = [0; 1024]; +use cortex_m::{ + asm::{bkpt, wfi}, + interrupt, +}; +use cortex_m_rt::entry; +use embedded_hal::spi::{Mode, Phase, Polarity}; +use stm32f1xx_hal::{ + pac, + prelude::*, + serial::{Config, Serial, StopBits, WordLength}, + spi::Spi, + usb::{self, UsbBus}, +}; +use usb_device::prelude::*; +use usbd_serial::{SerialPort, USB_CLASS_CDC}; #[entry] -fn main(_hartid: usize) -> ! { - let p = Peripherals::take().expect("couldn't take peripherals"); - - pac::ECLIC::reset(); - pac::ECLIC::set_threshold_level(eclic::Level::L0); - pac::ECLIC::set_level_priority_bits(eclic::LevelPriorityBits::L3P1); - - let mut rcu = p.RCU - .configure() - .ext_hf_clock(MegaHertz(8)) - .sysclk(MegaHertz(96)) - .freeze(); - let mut afio = p.AFIO.constrain(&mut rcu); - let gpioa = p.GPIOA.split(&mut rcu); - - // TODO: figure out how to use the usb serial on the start board. - // - // this version has to be wired up physically. - let serial = Serial::new( - p.USART1, - (gpioa.pa2, gpioa.pa3), - Default::default(), - &mut afio, - &mut rcu, +fn main() -> ! { + let dp = pac::Peripherals::take().unwrap(); + + let mut flash = dp.FLASH.constrain(); + let rcc = dp.RCC.constrain(); + + let clocks = rcc + .cfgr + .use_hse(8.MHz()) + .sysclk(72.MHz()) // TODO: gd32 can get up to 120MHz + // .pclk1(24.MHz()) // TODO: causes issues with gd32 usb (dropped packets) and garbled usart1 output + .freeze(&mut flash.acr); + + assert!(clocks.usbclk_valid()); + + let mut gpiob = dp.GPIOB.split(); + let mut led = LED::new(gpiob.pb2, &mut gpiob.crl); + + let mut afio = dp.AFIO.constrain(); + let mut gpioa = dp.GPIOA.split(); + + let tx_pin = gpioa.pa9.into_alternate_push_pull(&mut gpioa.crh); + let rx_pin = gpioa.pa10; + let serial = Serial::usart1( + dp.USART1, + (tx_pin, rx_pin), + &mut afio.mapr, + Config::default() + .baudrate(115200.bps()) + .wordlength(WordLength::Bits8) + .parity_none() + .stopbits(StopBits::STOP1), + clocks, ); - let (tx, _rx) = serial.split(); + let (tx, _) = serial.split(); + log::init(tx); - let timer = Timer::<pac::TIMER6>::timer6(p.TIMER6, Hertz(5), &mut rcu); - let led = LED::new(gpioa.pa7); - let mut blink = blink::Task::new(timer, Hertz(5), led); + logln!("luchie started!"); + + // cirque spi connections to spi1: + // + // pb0 - dr + // pa4 - ss1 + // pa5 - clk1 + // pa6 - miso1 + // pa7 - mosi1 + + let dr_pin = gpiob.pb0; + let sck_pin = gpioa.pa5.into_alternate_push_pull(&mut gpioa.crl); + let miso_pin = gpioa.pa6; + let mosi_pin = gpioa.pa7.into_alternate_push_pull(&mut gpioa.crl); + let cs_pin = gpioa.pa4.into_push_pull_output(&mut gpioa.crl); + let spi_mode = Mode { + phase: Phase::CaptureOnSecondTransition, + polarity: Polarity::IdleHigh, + }; + let spi = Spi::spi1( + dp.SPI1, + (sck_pin, miso_pin, mosi_pin), + &mut afio.mapr, + spi_mode, + 1.MHz(), + clocks, + ); - let usb = USB { - usb_global: p.USBFS_GLOBAL, - usb_device: p.USBFS_DEVICE, - usb_pwrclk: p.USBFS_PWRCLK, + // BluePill board has a pull-up resistor on the D+ line. + // 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(&mut gpioa.crh); + usb_dp.set_low(); + // let mut delay = dp.TIM2.delay_us(&clocks); + // delay.delay_ms(10u8); + cortex_m::asm::delay(clocks.sysclk().raw() / 100); + + let usb = usb::Peripheral { + usb: dp.USB, pin_dm: gpioa.pa11, - pin_dp: gpioa.pa12, - hclk: rcu.clocks.hclk() + pin_dp: usb_dp.into_floating_input(&mut gpioa.crh), }; + let usb_bus = UsbBus::new(usb); - let usb_bus = UsbBus::new(usb, unsafe { &mut EP_MEMORY }); + let mut serial = SerialPort::new(&usb_bus); - let mut usb_dev = UsbDeviceBuilder::new(&usb_bus, UsbVidPid(0x16c0, 0x27dd)) + let mut usb_dev = UsbDeviceBuilder::new(&usb_bus, UsbVidPid(0xdead, 0xbeef)) .manufacturer("Fake company") - .product("Enumeration test") + .product("Serial port") .serial_number("TEST") - .device_class(0) + .device_class(USB_CLASS_CDC) .build(); - //let mut serial = SerialPort::new(&bus_alloc); - - unsafe { interrupt::enable() }; - loop { - let mut can_sleep = true; - - if let Ok(_) = blink.poll() { - can_sleep = false; - } - if usb_dev.poll(&mut []) { - logln!("usb"); - can_sleep = false; + logln!("."); + if !usb_dev.poll(&mut [&mut serial]) { + continue; } - if can_sleep && false { - log!("!"); - unsafe { wfi() }; + let mut buf = [0u8; 64]; + + match serial.read(&mut buf) { + Ok(count) if count > 0 => { + led.on(); + + // 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; + } + _ => {} + } + } + } + _ => {} } - } -} -#[export_name="ExceptionHandler"] -fn exception_handler(_frame: &riscv_rt::TrapFrame) -> ! { - spin(); -} - -#[export_name="DefaultHandler"] -fn default_handler() -> ! { - spin(); -} -#[export_name="MachineTimer"] -fn machine_timer() { - spin(); -} -*/ - -#![no_std] -#![no_main] - -mod usb; - -use riscv::asm::wfi; -use riscv_rt::entry; -use gd32vf103xx_hal::prelude::*; -use gd32vf103xx_hal::pac; - -use usb::{USB, UsbBus}; -use usb_device::prelude::*; -use usbd_serial::SerialPort; - -static mut EP_MEMORY: [u32; 1024] = [0; 1024]; - -#[entry] -fn main() -> ! { - let dp = pac::Peripherals::take().unwrap(); - - // Configure clocks - let mut rcu = dp.RCU.configure() - .ext_hf_clock(8.mhz()) - .sysclk(96.mhz()) - .freeze(); - - assert!(rcu.clocks.usbclk_valid()); - - let gpioa = dp.GPIOA.split(&mut rcu); - let usb = USB { - usb_global: dp.USBFS_GLOBAL, - usb_device: dp.USBFS_DEVICE, - usb_pwrclk: dp.USBFS_PWRCLK, - pin_dm: gpioa.pa11, - pin_dp: gpioa.pa12, - hclk: rcu.clocks.hclk() - }; - - let usb_bus = UsbBus::new(usb, unsafe { &mut EP_MEMORY }); - - let mut serial = SerialPort::new(&usb_bus); - let mut usb_dev = UsbDeviceBuilder::new(&usb_bus, UsbVidPid(0x16c0, 0x27dd)) - .manufacturer("Fake company") - .product("Enumeration test") - .serial_number("TEST") - .device_class(0) - .build(); - - loop { - if usb_dev.poll(&mut [&mut serial]) { - } + led.off(); } } #[panic_handler] fn panic(info: &core::panic::PanicInfo) -> ! { -// interrupt::free(|_cs| { -// log!("!!! panic "); + interrupt::free(|_cs| { + log!("!!! panic "); if let Some(loc) = info.location() { -// log!("in {}:{} ", loc.file(), loc.line()); + log!("in {}:{} ", loc.file(), loc.line()); } if let Some(msg) = info.payload().downcast_ref::<&str>() { -// log!("⇒ {} ", msg); + log!("⇒ {} ", msg); } -// logln!("!!!"); -// }); + logln!("!!!"); + }); spin(); } fn spin() -> ! { - loop { unsafe { wfi() } }; + bkpt(); + loop { + wfi(); + } } diff --git a/src/usb.rs b/src/usb.rs deleted file mode 100755 index 1ec36af..0000000 --- a/src/usb.rs +++ /dev/null @@ -1,42 +0,0 @@ -use gd32vf103xx_hal::pac; -use gd32vf103xx_hal::gpio::{Input, Floating, gpioa::{PA11, PA12}}; -use gd32vf103xx_hal::time::Hertz; -pub use synopsys_usb_otg::UsbBus; -use synopsys_usb_otg::UsbPeripheral; - -#[allow(dead_code)] -pub struct USB { - pub usb_global: pac::USBFS_GLOBAL, - pub usb_device: pac::USBFS_DEVICE, - pub usb_pwrclk: pac::USBFS_PWRCLK, - pub pin_dm: PA11<Input<Floating>>, - pub pin_dp: PA12<Input<Floating>>, - pub hclk: Hertz, -} - -unsafe impl Sync for USB {} - -unsafe impl UsbPeripheral for USB { - const REGISTERS: *const () = pac::USBFS_GLOBAL::ptr() as *const (); - - const HIGH_SPEED: bool = false; - const FIFO_DEPTH_WORDS: usize = 320; - const ENDPOINT_COUNT: usize = 4; - - fn enable() { - let rcu = unsafe { &*pac::RCU::ptr() }; - - riscv::interrupt::free(|_| { - // Enable USB peripheral - rcu.ahben.modify(|_, w| w.usbfsen().set_bit()); - - // Reset USB peripheral - rcu.ahbrst.modify(|_, w| w.usbfsrst().set_bit()); - rcu.ahbrst.modify(|_, w| w.usbfsrst().clear_bit()); - }); - } - - fn ahb_frequency_hz(&self) -> u32 { - self.hclk.0 - } -} |