mirror of https://github.com/ArduPilot/ardupilot
153 lines
2.9 KiB
Plaintext
153 lines
2.9 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# for mini-pix hardware from RadioLink
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F4xx STM32F405xx
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 3
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 24000000
|
|
|
|
# ChibiOS system timer
|
|
STM32_ST_USE_TIMER 5
|
|
|
|
FLASH_SIZE_KB 1024
|
|
|
|
|
|
# use USB for stdout, so no STDOUT_SERIAL
|
|
# STDOUT_SERIAL SD2
|
|
# STDOUT_BAUDRATE 57600
|
|
|
|
# only one I2C bus
|
|
I2C_ORDER I2C2 I2C1
|
|
|
|
# order of UARTs (and USB)
|
|
SERIAL_ORDER OTG1 USART3 USART2 UART4
|
|
|
|
# UART4 serial GPS
|
|
PA0 UART4_TX UART4
|
|
PA1 UART4_RX UART4
|
|
PA2 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
|
PA3 BATT_CURRENT_SENS ADC1 SCALE(1)
|
|
PA4 VDD_5V_SENS ADC1 SCALE(2)
|
|
#SPI for MPU6500
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
|
|
# setup for power brick
|
|
define HAL_BATT_VOLT_PIN 2
|
|
define HAL_BATT_CURR_PIN 3
|
|
define HAL_BATT_VOLT_SCALE 12.1
|
|
define HAL_BATT_CURR_SCALE 43.0
|
|
|
|
PA9 VBUS INPUT OPENDRAIN
|
|
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
PA15 TIM2_CH1 TIM2 GPIO(77) ALARM
|
|
|
|
PB0 TIM3_CH3 TIM3 PPMIN # RC Input PPM
|
|
PB2 BOOT1 INPUT
|
|
|
|
PB5 VDD_BRICK_VALID INPUT PULLDOWN
|
|
|
|
PB8 I2C1_SCL I2C1
|
|
PB9 I2C1_SDA I2C1
|
|
|
|
PB10 I2C2_SCL I2C2
|
|
PB11 I2C2_SDA I2C2
|
|
|
|
PB13 SPI2_SCK SPI2
|
|
PB14 SPI2_MISO SPI2
|
|
PB15 SPI2_MOSI SPI2
|
|
|
|
PC0 VBUS_VALID INPUT PULLDOWN
|
|
PC1 RSSI_IN ADC1
|
|
PC2 LPS22HB_CS CS
|
|
PC3 LED_SAFETY OUTPUT
|
|
PC4 SAFETY_IN INPUT
|
|
|
|
# default to RCIN using timer capture
|
|
PC7 TIM8_CH2 TIM8 RCININT PULLDOWN
|
|
|
|
|
|
PC8 SDIO_D0 SDIO
|
|
PC9 SDIO_D1 SDIO
|
|
PC10 SDIO_D2 SDIO
|
|
PC11 SDIO_D3 SDIO
|
|
PC12 SDIO_CK SDIO
|
|
|
|
PC13 SBUS_INV OUTPUT
|
|
PC14 MPU6500_DRDY INPUT
|
|
PC15 MPU6500_CS CS
|
|
|
|
PD2 SDIO_CMD SDIO
|
|
|
|
# USART2 serial2 telem2
|
|
PD3 USART2_CTS USART2
|
|
PD4 USART2_RTS USART2
|
|
PD5 USART2_TX USART2
|
|
PD6 USART2_RX USART2
|
|
|
|
# USART3 serial3 telem1
|
|
PD8 USART3_TX USART3
|
|
PD9 USART3_RX USART3
|
|
PD10 FRAM_CS CS
|
|
PD11 USART3_CTS USART3
|
|
PD12 USART3_RTS USART3
|
|
|
|
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
|
|
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
|
|
|
|
PD15 LPS22HB_DRDY INPUT
|
|
|
|
PE3 VDD_SENSORS_EN OUTPUT HIGH
|
|
|
|
PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53)
|
|
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
|
|
PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51)
|
|
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
|
|
|
|
# SPI devices
|
|
SPIDEV mpu6000 SPI1 DEVID1 MPU6500_CS MODE3 1*MHZ 8*MHZ
|
|
SPIDEV lps22h SPI2 DEVID3 LPS22HB_CS MODE3 1*MHZ 10*MHZ
|
|
SPIDEV ramtron SPI2 DEVID4 FRAM_CS MODE3 8*MHZ 8*MHZ
|
|
|
|
# one baro
|
|
BARO LPS2XH SPI:lps22h
|
|
|
|
# one IMU
|
|
IMU Invensense SPI:mpu6000 ROTATION_PITCH_180
|
|
|
|
# one internal compass, plus external probe
|
|
COMPASS QMC5883L I2C:0:0x0D false ROTATION_PITCH_180_YAW_270
|
|
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
|
define HAL_I2C_INTERNAL_MASK 1
|
|
|
|
define HAL_STORAGE_SIZE 16384
|
|
|
|
# enable RAMTROM parameter storage
|
|
define HAL_WITH_RAMTRON 1
|
|
|
|
# enable FAT filesystem
|
|
define HAL_OS_FATFS_IO 1
|
|
|
|
# LED setup is similar to PixRacer
|
|
define HAL_HAVE_PIXRACER_LED
|
|
PB1 LED_RED OUTPUT GPIO(0)
|
|
PC5 LED_GREEN OUTPUT GPIO(1)
|
|
PE12 LED_BLUE OUTPUT GPIO(2)
|
|
|
|
define HAL_GPIO_A_LED_PIN 0
|
|
define HAL_GPIO_B_LED_PIN 1
|
|
define HAL_GPIO_C_LED_PIN 2
|
|
|
|
define HAL_GPIO_LED_ON 0
|
|
define HAL_GPIO_LED_OFF 1
|
|
|
|
include ../include/minimize_features.inc
|
|
|