Skip to content

Commit

Permalink
hwdef: new board: FlysparkF4
Browse files Browse the repository at this point in the history
  • Loading branch information
magicrub committed Jul 25, 2024
1 parent c4413b0 commit 966ba2a
Show file tree
Hide file tree
Showing 2 changed files with 50 additions and 45 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_HAL_ChibiOS/hwdef/FlysparkF4/hwdef-bl.dat
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ FLASH_SIZE_KB 1024
FLASH_RESERVE_START_KB 0

# LEDs
PBC13 LED_BOOTLOADER OUTPUT LOW
PC13 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0

# the location where the bootloader will put the firmware
Expand All @@ -30,7 +30,7 @@ PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

# Add CS pins to ensure they are high in bootloader
PA4 ICM42688_SPI6_CS CS
PA4 ICM42688_CS CS
PB12 MAX7456_CS CS
PC14 SDCARD_CS CS

91 changes: 48 additions & 43 deletions libraries/AP_HAL_ChibiOS/hwdef/FlysparkF4/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -12,25 +12,25 @@ APJ_BOARD_ID 1361
# crystal frequency
OSCILLATOR_HZ 8000000

define STM32_ST_USE_TIMER 4
define STM32_ST_USE_TIMER 5
define CH_CFG_ST_RESOLUTION 16

FLASH_SIZE_KB 1024


# only one I2C bus
I2C_ORDER I2C1

# order of UARTs (and USB)
SERIAL_ORDER OTG1 USART3 UART4 USART1 UART5 USART2

# Spare GPIO
PB11 PINIO OUTPUT HIGH GPIO(1)

# LEDs
#define AP_NOTIFY_GPIO_LED_2_ENABLED 1
#PB9 LED_BLUE OUTPUT LOW GPIO(0)
#PA14 LED_GREEN OUTPUT LOW GPIO(1)
PC13 LED0 OUTPUT HIGH GPIO(2)
define HAL_GPIO_A_LED_PIN 2
define AP_NOTIFY_GPIO_LED_1_ENABLED 1
define AP_NOTIFY_GPIO_LED_A_PIN 2


#define HAL_GPIO_A_LED_PIN 0
#define HAL_GPIO_B_LED_PIN 1

# buzzer
PC15 BUZZER OUTPUT GPIO(80) LOW
Expand All @@ -43,6 +43,7 @@ PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
PA4 ICM42688_CS CS
PC4 ICM42688_INT INPUT PULLDOWN

# spi2 for OSD
PB13 SPI2_SCK SPI2
Expand All @@ -63,52 +64,50 @@ PB9 I2C1_SDA I2C1
# analog pins
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
PC5 RSSI_ADC_PIN ADC1 SCALE(1)

# define default battery setup
# PC5 - ADC12_CH15
define HAL_BATT_VOLT_PIN 15
# PC4 - ADC12_CH14
define HAL_BATT_CURR_PIN 14
#analog rssi pin (also could be used as analog airspeed input)
PC5 RSSI_IN ADC1 SCALE(1)
define BOARD_RSSI_ANA_PIN 15

#define HAL_BATT_VOLT_PIN 10
#define HAL_BATT_CURR_PIN 11
define HAL_BATT_VOLT_SCALE 10.1
define HAL_BATT_CURR_SCALE 17.0

#analog rssi pin (also could be used as analog airspeed input)
# PB1 - ADC12_CH9
define BOARD_RSSI_ANA_PIN 9

# USART1
# USART1 (DJI)
PA9 USART1_TX USART1
PA10 USART1_RX USART1
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_DJI_FPV

# RC input using timer
PB15 TIM12_CH2 TIM12 RCININT PULLDOWN

# alternative RC input using UART
PA2 USART2_TX USART2 NODMA
PA3 USART2_RX USART2 NODMA
# UART2 (RC input)
PA2 USART2_TX USART2
PA3 USART2_RX USART2
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN

# USART3
PC10 USART3_TX USART3
PC11 USART3_RX USART3

# UART4
# UART4 (ESP32)
PA0 UART4_TX UART4
PA1 UART4_RX UART4

# UART5
PD2 UART5_RX UART5
#???? UART5_TX UART5

# UART6
# UART6 (DJI)
PC7 USART6_RX USART6
PC6 USART6_TX USART6

# PA10 IO-debug-console
# USB
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

# debug (disabled out to allow for both LEDs)
# order of UARTs (and USB)
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6

# debug
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD

Expand All @@ -123,32 +122,38 @@ PC9 TIM3_CH4 TIM3 PWM(6) GPIO(55)
PB10 TIM2_CH3 TIM2 PWM(7) GPIO(56)
PA15 TIM2_CH1 TIM2 PWM(8) GPIO(57)

# NeoPixel LED strip
PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58)

# RC input using timer
PB15 TIM12_CH2 TIM12 RCININT PULLDOWN LOW


define HAL_STORAGE_SIZE 15360
STORAGE_FLASH_PAGE 2

# reserve 32k for bootloader and 32k for flash storage
FLASH_RESERVE_START_KB 64

# one IMU
IMU Invensense SPI:mpu6000 ROTATION_YAW_180

# probe for I2C BMP280, but allow init on board variants without onboard baro too
BARO BMP280 I2C:0:0x76
define HAL_BARO_ALLOW_INIT_NO_BARO
define AP_BARO_BACKEND_DEFAULT_ENABLED 0
define AP_BARO_BMP280_ENABLED 1

# 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_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2

# SPI devices
SPIDEV mpu6000 SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 8*MHZ
SPIDEV sdcard SPI3 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
SPIDEV osd SPI2 DEVID1 MAX7456_CS MODE0 10*MHZ 10*MHZ

# spi devices
SPIDEV icm42688 SPI1 DEVID1 ICM42688_CS MODE3 2*MHZ 8*MHZ
SPIDEV osd SPI2 DEVID2 MAX7456_CS MODE0 10*MHZ 10*MHZ
SPIDEV sdcard SPI3 DEVID3 SDCARD_CS MODE0 400*KHZ 25*MHZ

# IMUs
IMU Invensense SPI:icm42688 ROTATION_NONE

# DPS310 integrated on I2C2 bus, multiple possible choices for external barometer
BARO DPS310 I2C:0:0x76


# filesystem setup on sdcard
define HAL_OS_FATFS_IO 1
Expand Down

0 comments on commit 966ba2a

Please sign in to comment.