mirror of https://github.com/ArduPilot/ardupilot
182 lines
4.5 KiB
Plaintext
182 lines
4.5 KiB
Plaintext
# hw definition file for CSKY405
|
|
|
|
USB_STRING_MANUFACTURER "CSKY"
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F4xx STM32F405xx
|
|
|
|
# bootloader starts firmware at 48k
|
|
FLASH_RESERVE_START_KB 48
|
|
FLASH_SIZE_KB 1024
|
|
|
|
# store parameters in pages 11 and 12
|
|
STORAGE_FLASH_PAGE 1
|
|
define HAL_STORAGE_SIZE 15360
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1158
|
|
|
|
define STM32_ST_USE_TIMER 5
|
|
define CH_CFG_ST_RESOLUTION 32
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 8000000
|
|
|
|
|
|
# --------------------- LED -----------------------
|
|
PA14 LED0 OUTPUT LOW GPIO(90) # blue marked as ACT
|
|
PA13 LED1 OUTPUT LOW GPIO(91) # green marked as B/E
|
|
define HAL_GPIO_A_LED_PIN 91
|
|
define HAL_GPIO_B_LED_PIN 90
|
|
|
|
# --------------------- PWM -----------------------
|
|
PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) // S1
|
|
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) // S2
|
|
PC9 TIM8_CH4 TIM8 PWM(3) GPIO(52) // S3
|
|
PC8 TIM8_CH3 TIM8 PWM(4) GPIO(53) // S4
|
|
|
|
PB11 TIM2_CH4 TIM2 PWM(5) GPIO(54) // S5
|
|
PB10 TIM2_CH3 TIM2 PWM(6) GPIO(55) // S6
|
|
PB9 TIM4_CH4 TIM4 PWM(7) GPIO(57) NODMA // S7
|
|
PB15 TIM12_CH2 TIM12 PWM(8) GPIO(58) NODMA // S8
|
|
|
|
PB14 TIM12_CH1 TIM12 PWM(9) GPIO(59) NODMA // S9
|
|
PA5 TIM2_CH1 TIM2 PWM(10) GPIO(60) NODMA // S10
|
|
|
|
define STM32_PWM_USE_ADVANCED TRUE
|
|
|
|
# Beeper
|
|
PC13 BUZZER OUTPUT GPIO(80) LOW
|
|
define HAL_BUZZER_PIN 80
|
|
|
|
# GPIOs
|
|
PB2 PINIO1 OUTPUT GPIO(81) LOW
|
|
PB8 PINIO2 OUTPUT GPIO(82) LOW
|
|
PC15 PINIO3 OUTPUT GPIO(83) LOW
|
|
PC0 PINIO4 OUTPUT GPIO(84) HIGH # BEC 12V enable
|
|
|
|
# --------------------- SPI1 -----------------------
|
|
PB3 SPI1_SCK SPI1
|
|
PB4 SPI1_MISO SPI1
|
|
PB5 SPI1_MOSI SPI1
|
|
|
|
PC14 BMI088_A_CS CS
|
|
PA4 BMI088_G_CS CS
|
|
|
|
# --------------------- SPI2 -----------------------
|
|
PB13 SPI2_SCK SPI2
|
|
PC2 SPI2_MISO SPI2
|
|
PC3 SPI2_MOSI SPI2
|
|
|
|
PB12 OSD_CS CS
|
|
PC1 SDCARD_CS CS
|
|
|
|
# -------------------- I2C bus --------------------
|
|
I2C_ORDER I2C1
|
|
|
|
PB6 I2C1_SCL I2C1
|
|
PB7 I2C1_SDA I2C1
|
|
|
|
define HAL_I2C_INTERNAL_MASK 0
|
|
|
|
# --------------------- UARTs ---------------------------
|
|
SERIAL_ORDER OTG1 UART4 USART1 UART5 USART3 USART6 USART2
|
|
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
# USART1
|
|
PA9 USART1_TX USART1
|
|
PA10 USART1_RX USART1
|
|
|
|
# USART2 (RCIN with inverter)
|
|
# alternative using USART2
|
|
PA2 USART2_TX USART2
|
|
PA3 USART2_RX USART2 ALT(1)
|
|
|
|
# default to timer for RC input
|
|
PA3 TIM9_CH2 TIM9 RCININT PULLDOWN LOW
|
|
|
|
# USART3
|
|
PC10 USART3_TX USART3
|
|
PC11 USART3_RX USART3
|
|
|
|
# UART4
|
|
PA0 UART4_TX UART4 NODMA
|
|
PA1 UART4_RX UART4 NODMA
|
|
|
|
# UART5, for GPS
|
|
PC12 UART5_TX UART5 NODMA
|
|
PD2 UART5_RX UART5 NODMA
|
|
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_GPS
|
|
define HAL_SERIAL3_BAUD AP_SERIALMANAGER_GPS_BAUD
|
|
|
|
# USART6
|
|
PC6 USART6_TX USART6
|
|
PC7 USART6_RX USART6 NODMA
|
|
|
|
# ------------------- DMA assignment -------------------
|
|
DMA_PRIORITY SPI1* UART2* TIM1* TIM8* TIM3* SPI2* ADC1
|
|
|
|
# ------------------- IMU BMI088 ---------------------
|
|
SPIDEV bmi088_g SPI1 DEVID1 BMI088_G_CS MODE3 10*MHZ 10*MHZ
|
|
SPIDEV bmi088_a SPI1 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ
|
|
IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180_YAW_270
|
|
#define HAL_DEFAULT_INS_FAST_SAMPLE 1
|
|
|
|
|
|
# ------------------ OSD AT7456E ----------------------
|
|
SPIDEV osd SPI2 DEVID2 OSD_CS MODE0 10*MHZ 10*MHZ
|
|
|
|
define OSD_ENABLED 1
|
|
define HAL_OSD_TYPE_DEFAULT 1
|
|
ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin
|
|
|
|
|
|
# --------------------- SD & FLASH ----------------------
|
|
SPIDEV sdcard SPI2 DEVID3 SDCARD_CS MODE3 104*MHZ 104*MHZ
|
|
|
|
#define HAL_LOGGING_DATAFLASH_ENABLED 1
|
|
|
|
define HAL_OS_FATFS_IO 1
|
|
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
|
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
|
|
|
# ----------------- I2C compass & Baro -----------------
|
|
# no built-in compass, but probe the i2c bus for all possible
|
|
# external compass types
|
|
define ALLOW_ARM_NO_COMPASS
|
|
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
|
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
|
|
|
# built-in barometer
|
|
BARO BMP388 I2C:0:0x77
|
|
|
|
# --------------------- ADC ---------------------------
|
|
PC4 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
|
PA7 BATT_CURRENT_SENS ADC1 SCALE(1)
|
|
PC5 RSSI_ADC_PIN ADC1 SCALE(1)
|
|
|
|
define HAL_BATT_MONITOR_DEFAULT 4
|
|
|
|
define HAL_BATT_VOLT_PIN 14
|
|
define HAL_BATT_VOLT_SCALE 21.0
|
|
|
|
define HAL_BATT_CURR_PIN 7
|
|
define HAL_BATT_CURR_SCALE 10.35
|
|
|
|
define BOARD_RSSI_ANA_PIN 15
|
|
define HAL_DEFAULT_AIRSPEED_PIN 10
|
|
|
|
# -------reduce max size of embedded params for apj_tool.py
|
|
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
|
|
|
|
# --------------------- save flash ----------------------
|
|
# save some flash
|
|
include ../include/minimize_fpv_osd.inc
|
|
include ../include/no_bootloader_DFU.inc
|
|
|
|
define HAL_PARACHUTE_ENABLED 1
|
|
define HAL_RUNCAM_ENABLED 0
|
|
define HAL_BUTTON_ENABLED 0
|