Crates.io | px4flow_bsp |
lib.rs | px4flow_bsp |
version | 0.2.0 |
source | src |
created_at | 2020-07-02 17:27:39.5235 |
updated_at | 2020-09-30 23:15:58.237496 |
description | A board support package for the PX4FLOW optical flow sensor board |
homepage | |
repository | https://github.com/tstellanova/px4flow_bsp |
max_upload_size | |
id | 260714 |
size | 71,157 |
Rust no_std embedded hal board support package for the PX4FLOW optical flow sensor hardware.
The examples are designed to be used with a debug probe that supports J-Link / RTT. We provide a couple different ways to run these:
With the Segger tools (This is currently the default.)
With probe-run (This is WIP and may not work as expected.)
segger.gdb
runner./start_gdb_server_jlink.sh
JLinkRTTClient
probe-run
runnercargo run --example play --features rttdebug
Currently you need to configure your application to forward interrupts from app-level interrupt handlers, ie:
/// should be called whenever DMA2 completes a transfer
#[interrupt]
fn DMA2_STREAM1() {
// forward to board's interrupt handler
unsafe {
(*BOARD_PTR.load(Ordering::SeqCst)).handle_dma2_stream1_interrupt();
}
}
/// should be called whenever DCMI completes a frame
#[interrupt]
fn DCMI() {
// forward to board's interrupt handler
unsafe {
(*BOARD_PTR.load(Ordering::SeqCst)).handle_dcmi_interrupt();
}
}
This assumes you are using the cortex-m-rt crate
to construct your embedded application, and using its #[interrupt]
to handle interrupts.
Work in progress
rttdebug
feature. This is because
the PX4FLOW 1.x and 2.x boards only make the SWD interface available (no easy ITM solution).breakout
feature is intended for library development and debugging purposes.
Currently it's setup to work with the "DevEBox STM32F4XX_M Ver:3.0" board (STM32F407VGT6), which does not
include a l3gd20 gyro or eeprom, and eg the Arducam MT9V034 breakout board ("UC-396 RevA")Pin | Configuration |
---|---|
PA0 | UART4_TX ("TIM5_CH1" - N/C) |
PA1 | "TIM5_CH2" (unused - N/C) |
PA2 | TIM5_CH3_EXPOSURE (pulled low) |
PA3 | TIM5_CH4_STANDBY (pulled low) |
PA4 | DCMI_HSYNC |
PA5 | CAM_NRESET (tied to high) |
PA6 | DCMI_PIXCK |
PB6 | DCMI_D5 |
PB7 | DCMI_VSYNC |
PB8 | I2C1 SCL |
PB9 | I2C1 SDA |
PB10 | I2C2 SCL |
PB11 | I2C2 SDA |
PB12 | spi_cs_gyro |
PB13 | SPI2 SCLK |
PB14 | SPI2 CIPO |
PB15 | SPI2 COPI |
PC6 | DCMI_D0 |
PC7 | DCMI_D1 |
PC8 | XCLK |
PC9 | "TIM8_CH4_LED_OUT" (unused) |
PC10 | DCMI_D8 |
PC11 | UART4_RX |
PC12 | DCMI_D9 |
PD0 | TBD |
PD5 | TBD |
PD6 | TBD |
PD7 | TBD |
PD15 | TBD |
PE0 | DCMI_D2 |
PE1 | DCMI_D3 |
PE2 | user_led0 |
PE3 | user_led1 |
PE4 | DCMI_D4 |
PE5 | DCMI_D6 |
PE6 | DCMI_D7 |
PE7 | user_led2 |