i had 2 issues with kakute f7, well, realistically only 1 was a serious enough issue - it was related to random loss of dshot data packets that looked like a loss of the power on one of the motors, so, drone would be fine in the air for a while, and at random spot it would either flip around or crash or just jerk as if it lost one of motors temporarily. it was correlated in the logs with the loss of telemetry data from that esc.
the fix was to set a NODMA clause in the build file on the UARTs. it was not confirmed, it is not the fact, and is not in the official master build, but i used this workaround in all my files and did not have any issues since that.
if you have same issue or not - i cannot say.
also, if drone flips immediately after startup - then most likely the PWMs are not mapped correctly to motors. the file i had done wa done for F7 AIO kakute, a regular F7 hs slightly different mapping usually, of what pwm goes to what motor.
it does not let me to attach that hwdef file - here it is, with the NODMA fix.
hw definition file for processing by chibios_pins.py
for Holybro KakuteF7 hardware.
@ thanks to betaflight for pin information
MCU class and specific type
MCU STM32F7xx STM32F745xx
board ID for firmware load
APJ_BOARD_ID 123
crystal frequency, setup to use external oscillator
OSCILLATOR_HZ 8000000
define STM32_LSECLK 32768U
define STM32_LSEDRV (3U << 3U)
define STM32_PLLSRC STM32_PLLSRC_HSE
define STM32_PLLM_VALUE 8
define STM32_PLLN_VALUE 432
define STM32_PLLP_VALUE 2
define STM32_PLLQ_VALUE 9
FLASH_SIZE_KB 1024
leave 2 sectors free
FLASH_RESERVE_START_KB 96
board voltage
STM32_VDD 330U
only one I2C bus
I2C_ORDER I2C1
order of UARTs (and USB), USART3 should be in second place to map order with the board’s silk screen
UART_ORDER OTG1 USART3 USART1 USART2 UART4 UART7 USART6
buzzer
PD15 TIM4_CH4 TIM4 GPIO(77) ALARM
PA10 IO-debug-console
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
SPI1 for SDCard
PA4 SDCARD_CS CS
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
SPI2 for MAX7456 OSD
PB12 MAX7456_CS CS
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
SPI4 for ICM20689
PE4 ICM20689_CS CS
PE2 SPI4_SCK SPI4
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4
I2C1 for baro
PB6 I2C1_SCL I2C1
PB7 I2C1_SDA I2C1
PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)
define default battery setup
define HAL_BATT_VOLT_PIN 13
define HAL_BATT_CURR_PIN 12
define HAL_BATT_VOLT_SCALE 10.1
define HAL_BATT_CURR_SCALE 17.0
PC5 RSSI_ADC ADC1
PA2 LED0 OUTPUT LOW
USART1
PA10 USART1_RX USART1 NODMA
PA9 USART1_TX USART1 NODMA
USART2
PD5 USART2_TX USART2 NODMA
PD6 USART2_RX USART2 NODMA
USART3 (GPS)
PB11 USART3_RX USART3 NODMA
PB10 USART3_TX USART3 NODMA
UART4 (GPS2)
PA0 UART4_TX UART4 NODMA
PA1 UART4_RX UART4 NODMA
USART6, RX only for RCIN
PC7 TIM8_CH2 TIM8 RCININT FLOAT LOW
PC6 USART6_TX USART6 NODMA LOW
UART7 USED BY ESC FROM ORIGINAL DESIGN
PE7 UART7_RX UART7 NODMA
PE8 UART7_TX UART7 NODMA
Motors
PB1 TIM1_CH3N TIM1 PWM(1) GPIO(50)
PE9 TIM1_CH1 TIM1 PWM(2) GPIO(51)
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
PB0 TIM3_CH3 TIM3 PWM(4) GPIO(53)
PC9 TIM3_CH4 TIM3 PWM(5) GPIO(54)
PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55)
PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) NODMA
#PD12 is repurposed for 7th PWM, originally intended as a LED strip pin
DMA_PRIORITY S*
define HAL_STORAGE_SIZE 16384
define STORAGE_FLASH_PAGE 1
spi devices
SPIDEV mpu6000 SPI4 DEVID1 ICM20689_CS MODE3 1MHZ 4MHZ
SPIDEV sdcard SPI1 DEVID1 SDCARD_CS MODE0 400KHZ 25MHZ
SPIDEV osd SPI2 DEVID4 MAX7456_CS MODE0 10MHZ 10MHZ
define HAL_BARO_DEFAULT HAL_BARO_BMP280_I2C
define HAL_BARO_BMP280_BUS 0
define HAL_BARO_BMP280_I2C_ADDR 0x76
no built-in compass, but probe the i2c bus for all possible
external compass types
define ALLOW_ARM_NO_COMPASS
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
probe for an invensense IMU
define HAL_INS_DEFAULT HAL_INS_MPU60XX_SPI
define HAL_INS_DEFAULT_ROTATION ROTATION_YAW_180
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY “/APM/LOGS”
define HAL_BOARD_TERRAIN_DIRECTORY “/APM/TERRAIN”
setup for OSD
define OSD_ENABLED ENABLED
define HAL_OSD_TYPE_DEFAULT 1
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
define BOARD_PWM_COUNT_DEFAULT 7
define STM32_PWM_USE_ADVANCED TRUE