mirror of https://github.com/ArduPilot/ardupilot
145 lines
3.0 KiB
Plaintext
145 lines
3.0 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# for Sparky2 hardware
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F4xx STM32F405xx
|
|
|
|
RAM_SIZE_KB 128
|
|
CCM_RAM_SIZE_KB 64
|
|
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 70
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 8000000
|
|
STM32_PLLM_VALUE 8
|
|
|
|
define STM32_ST_USE_TIMER 5
|
|
|
|
FLASH_SIZE_KB 1024
|
|
|
|
# board voltage
|
|
STM32_VDD 330U
|
|
|
|
# serial port for stdout via flexi-port (conn3)
|
|
STDOUT_SERIAL SD1
|
|
STDOUT_BAUDRATE 115200
|
|
|
|
# --------LEDs-----------
|
|
PB5 LED_BLUE OUTPUT LOW GPIO(0)
|
|
PB6 LED_YELLOW OUTPUT LOW GPIO(1) # optional
|
|
PB4 LED_RED OUTPUT LOW 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
|
|
|
|
# ---------I2C-------------
|
|
# only one I2C bus
|
|
I2C_ORDER I2C1
|
|
|
|
PB8 I2C1_SCL I2C1
|
|
PB9 I2C1_SDA I2C1
|
|
|
|
# -------BARO-------------
|
|
define HAL_BARO_DEFAULT HAL_BARO_MS5611_I2C
|
|
define HAL_BARO_MS5611_I2C_BUS 0
|
|
define HAL_BARO_MS5611_I2C_ADDR 0x77
|
|
|
|
# ---------USB-------------
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
PA8 VBUS INPUT OPENDRAIN
|
|
|
|
# ---------UARTS-----------
|
|
# order of UARTs (and USB)
|
|
UART_ORDER OTG1 USART1 USART3
|
|
|
|
# Main PORT
|
|
PA9 USART1_TX USART1
|
|
PA10 USART1_RX USART1
|
|
|
|
# Flex PORT
|
|
PB10 USART3_TX USART3
|
|
PB11 USART3_RX USART3
|
|
|
|
# -------RCIN-------------
|
|
# Soft Serial for serial RC & PPM
|
|
PC7 TIM8_CH2 TIM8 RCIN FLOAT LOW
|
|
PC6 SBUS_INVERT OUTPUT
|
|
|
|
# -------ADC-------------
|
|
analog pins
|
|
PC1 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
|
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)
|
|
|
|
# define default battery setup No Voltage Divider
|
|
define HAL_BATT_VOLT_PIN 12
|
|
define HAL_BATT_CURR_PIN 13
|
|
define HAL_BATT_VOLT_SCALE 10.1
|
|
define HAL_BATT_CURR_SCALE 17.0
|
|
|
|
# -----CAN BUS-------------
|
|
PB13 CAN2_TX CAN2
|
|
PB12 CAN2_RX CAN2
|
|
|
|
# -----spi bus for IMU-----
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
PC4 MPU_CS CS
|
|
PC5 EXTI_MPU9250 INPUT PULLUP
|
|
|
|
# -----spi bus for FLASH-----
|
|
PC10 SPI3_SCK SPI3
|
|
PC11 SPI3_MISO SPI3
|
|
PC12 SPI3_MOSI SPI3
|
|
PB3 FLASH_CS CS
|
|
|
|
# -----USB & SWD-----------
|
|
# PA10 IO-debug-console
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# ----------PWM-----------
|
|
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50)
|
|
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51)
|
|
PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52)
|
|
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53)
|
|
PA1 TIM2_CH2 TIM2 PWM(5) GPIO(54)
|
|
PA0 TIM2_CH1 TIM2 PWM(6) GPIO(55)
|
|
|
|
# Buffered PWM N-Fets----
|
|
# Require inverter to use
|
|
# as standard pwm
|
|
# PC9 TIM8_CH4 TIM8 PWM(7)
|
|
# PC8 TIM8_CH3 TIM8 PWM(8)
|
|
# PB15 TIM8_CH3N TIM8 PWM(9)
|
|
PB14 TIM1_CH2N TIM1 PWM(7) GPIO(35)
|
|
|
|
define HAL_STORAGE_SIZE 8192
|
|
define STORAGE_FLASH_PAGE 1
|
|
|
|
FLASH_SIZE_KB 1024
|
|
|
|
# reserve 16k for bootloader and 32k for flash storage
|
|
FLASH_RESERVE_START_KB 64
|
|
|
|
define HAL_INS_DEFAULT HAL_INS_MPU9250_SPI
|
|
define HAL_COMPASS_DEFAULT HAL_COMPASS_AK8963_MPU9250
|
|
|
|
|
|
# SPI devices
|
|
SPIDEV mpu9250 SPI1 DEVID4 MPU_CS MODE3 1*MHZ 4*MHZ
|
|
SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 1*MHZ 8*MHZ
|
|
|
|
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_SPARKY2
|
|
|
|
define STM32_PWM_USE_ADVANCED TRUE
|
|
|
|
define BOARD_PWM_COUNT_DEFAULT 7
|