HAL_ChibiOS: support for CUAVv5Nano board

F765 with no IOMCU
This commit is contained in:
Andrew Tridgell 2019-03-01 14:37:28 +11:00 committed by Tom Pittenger
parent ad75b1e56f
commit ce4abf8dcb
2 changed files with 128 additions and 0 deletions

View File

@ -0,0 +1,59 @@
# hw definition file for processing by chibios_hwdef.py
# CUAVv5Nano
# MCU class and specific type
MCU STM32F7xx STM32F767xx
# crystal frequency
OSCILLATOR_HZ 16000000
define STM32_LSECLK 32768U
define STM32_LSEDRV (3U << 3U)
define STM32_PLLSRC STM32_PLLSRC_HSE
define STM32_PLLM_VALUE 8
define STM32_PLLN_VALUE 216
define STM32_PLLP_VALUE 2
define STM32_PLLQ_VALUE 9
# board ID for firmware load
APJ_BOARD_ID 50
FLASH_SIZE_KB 2048
# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0
# the location where the bootloader will put the firmware
define FLASH_BOOTLOADER_LOAD_KB 32
# start with PE3 low
undef PE3
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
PC6 LED_BOOTLOADER OUTPUT HIGH
PC7 LED_ACTIVITY OUTPUT HIGH
define HAL_LED_ON 0
# board voltage
STM32_VDD 330U
# order of UARTs (and USB)
UART_ORDER OTG1 USART2 UART7
# USART2 is telem1
PD6 USART2_RX USART2
PD5 USART2_TX USART2
PD3 USART2_CTS USART2
PD4 USART2_RTS USART2
PF6 UART7_RX UART7 NODMA
PE8 UART7_TX UART7 NODMA
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384

View File

@ -0,0 +1,69 @@
# hw definition file for processing by chibios_hwdef.py
# for CUAVv5Nano F7 hardware.
# This is a varient of fmuv5 without the IOMCU
include ../fmuv5/hwdef.dat
# we shift the system timer to TIM5 to allow
# us to use TIM2 for extra PWM outputs
STM32_ST_USE_TIMER 5
# start with PE3 low
undef PE3
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
# order of UARTs (and USB). Telem2 is UART4 on the mini, USART3 is not available
UART_ORDER OTG1 USART1 USART2 UART4 USART6 UART7
# enable TX on USART6 (disabled for fmuv5 with iomcu)
PG14 USART6_TX USART6 NODMA
# disable the IOMCU UART
undef IOMCU_UART
undef UART8_TX
undef UART8_RX
undef AP_FEATURE_SBUS_OUT
# allow the first 3 capture ports to be used as PWM outputs or GPIOs
undef PA5
undef PB3
undef PB11
undef FMU_CAP1
undef FMU_CAP2
undef FMU_CAP3
PA5 TIM2_CH1 TIM2 PWM(9) GPIO(58)
PB3 TIM2_CH2 TIM2 PWM(10) GPIO(59)
PB11 TIM2_CH4 TIM2 PWM(11) GPIO(60)
# RCInput on the PPM pin, for all protocols
undef PG9
undef USART6_RX
PI5 TIM8_CH1 TIM8 RCININT PULLUP LOW
# setup for supplied power brick
undef HAL_BATT_VOLT_SCALE
define HAL_BATT_VOLT_SCALE 18.182
undef HAL_BATT_CURR_SCALE
define HAL_BATT_CURR_SCALE 36.364
# setup safety switch
PE12 LED_SAFETY OUTPUT
PE10 SAFETY_IN INPUT PULLDOWN
# extra LEDs, active low, used using the pixracer LED scheme
PH10 LED_R OUTPUT HIGH GPIO(0)
PH11 LED_G OUTPUT HIGH GPIO(1)
PH12 LED_B OUTPUT HIGH GPIO(2)
undef HAL_GPIO_A_LED_PIN
undef HAL_GPIO_B_LED_PIN
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
define HAL_HAVE_PIXRACER_LED