HAL_Chibios: support modalai_fc-v1 flight controller
Based on M0018 version. Thanks to ModalAI for assistance
This commit is contained in:
parent
28c34bdce4
commit
7c3c3a0a41
68
libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/README.md
Normal file
68
libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/README.md
Normal file
@ -0,0 +1,68 @@
|
||||
# ModalAI Flight Core v1 Controller
|
||||
|
||||
The ModalAI FlightCore is a flight controller produced by [ModalAI](http://www.modalai.com/).
|
||||
|
||||
## Features
|
||||
|
||||
- STM32F765 microcontroller
|
||||
- ICM42688 and ICM20602 IMUs
|
||||
- BMP388 barometer
|
||||
- microSD card slot
|
||||
- 7 UARTs plus USB
|
||||
- 8 PWM outputs
|
||||
|
||||
## Pinout
|
||||
|
||||
![ModalAI_v1 Board](fc-overlay-top-144-dpi.jpg "ModalAI_v1")
|
||||
|
||||
For detailed pinout descriptions see [FlightCore Pinout](https://docs.modalai.com/flight-core-datasheets-connectors/)
|
||||
|
||||
## UART Mapping
|
||||
|
||||
The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the
|
||||
receive pin for UARTn. The Tn pin is the transmit pin for UARTn.
|
||||
|
||||
- SERIAL0 -> USB
|
||||
- SERIAL1 -> UART7 (Telem1)
|
||||
- SERIAL2 -> UART5 (Telem2)
|
||||
- SERIAL3 -> USART1 (GPS)
|
||||
- SERIAL4 -> UART4 (GPS2)
|
||||
- SERIAL5 -> USART2
|
||||
- SERIAL6 -> USART6 (spektrum RCIN)
|
||||
- SERIAL7 -> USART3
|
||||
- SERIAL8 -> USB2
|
||||
|
||||
## RC Input
|
||||
|
||||
RC input is configured on both the PPM input pin and the "spektrum"
|
||||
USART6 UART. The PPM pin supports all one-way RC protocols. For
|
||||
protocols requiring half-duplex serial to transmit telemetry (such as
|
||||
FPort) you should use the spektrum port, mapped to SERIAL6. Both PPM
|
||||
and spektrum ports are enabled for RCIN by default.
|
||||
|
||||
## PWM Output
|
||||
|
||||
The ModalAI_v1 supports up to 8 PWM outputs on the PWM output connector
|
||||
|
||||
The PWM is in 2 groups:
|
||||
|
||||
- PWM 1, 2, 3, 4 in group1
|
||||
- PWM 5, 6, 7, 8 in group2
|
||||
|
||||
Channels within the same group need to use the same output rate. If
|
||||
any channel in a group uses DShot then all channels in the group need
|
||||
to use DShot.
|
||||
|
||||
## Power Monitoring
|
||||
|
||||
In addition to the normal range of ArduPilot power monitoring options,
|
||||
the modalAI build supports two I2C power monitors, the INA231 and the
|
||||
LTC2946. The FlightCore board comes with the INA231 and you should set
|
||||
BATTERY_MONITOR to 21. For the LTC2946 based power brick you should
|
||||
set BATTERY_MONITOR to 22.
|
||||
|
||||
## Compass
|
||||
|
||||
The ModalAI_v1 does not have a built-in compass, but you can attach an
|
||||
external compass
|
||||
|
Binary file not shown.
After Width: | Height: | Size: 143 KiB |
76
libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/hwdef-bl.dat
Normal file
76
libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/hwdef-bl.dat
Normal file
@ -0,0 +1,76 @@
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for F765 bootloader
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F7xx STM32F767xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 41775
|
||||
|
||||
# default to all pins low to avoid ESD issues
|
||||
DEFAULTGPIO OUTPUT LOW PULLDOWN
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 32
|
||||
|
||||
PB1 LED_BOOTLOADER OUTPUT HIGH
|
||||
PB0 LED_ACTIVITY OUTPUT HIGH
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 UART7 UART5 USART2 USART3
|
||||
|
||||
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 32768
|
||||
|
||||
# UARTs
|
||||
|
||||
# USART2 is telem3, MSS_SPARE_4W
|
||||
PA3 USART2_RX USART2 NODMA
|
||||
PD5 USART2_TX USART2
|
||||
PD3 USART2_CTS USART2
|
||||
PD4 USART2_RTS USART2
|
||||
|
||||
# USART3, UART_2W_DEBUG
|
||||
PD9 USART3_RX USART3 NODMA
|
||||
PD8 USART3_TX USART3
|
||||
|
||||
# UART5 Telem 2, MSS_UART_4W
|
||||
PD2 UART5_RX UART5
|
||||
PB9 UART5_TX UART5
|
||||
PC8 UART5_RTS UART5
|
||||
PC9 UART5_CTS UART5
|
||||
|
||||
# UART7 Telem 1, TELEM_UART_4W
|
||||
PE7 UART7_RX UART7
|
||||
PE8 UART7_TX UART7
|
||||
PE9 UART7_RTS UART7
|
||||
PE10 UART7_CTS UART7
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PF3 ICM20602_CS CS SPEED_VERYLOW
|
||||
PF4 BMI088_G_CS CS
|
||||
PG10 BMI088_A_CS CS
|
||||
PF5 FRAM_CS CS SPEED_VERYLOW
|
||||
PF11 SPARE_CS CS
|
||||
PH5 AUXMEM_CS CS
|
||||
PI4 EXTERNAL1_CS1 CS
|
||||
PI10 EXTERNAL1_CS2 CS
|
||||
PI11 EXTERNAL1_CS3 CS
|
||||
PI6 EXTERNAL2_CS1 CS
|
||||
PI7 EXTERNAL2_CS2 CS
|
||||
PI8 EXTERNAL2_CS3 CS
|
280
libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/hwdef.dat
Normal file
280
libraries/AP_HAL_ChibiOS/hwdef/modalai_fc-v1/hwdef.dat
Normal file
@ -0,0 +1,280 @@
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for Modal AI FC v1
|
||||
|
||||
# MCU class and specific type. It is a F765, which is the same as F767
|
||||
# but without the TFT interface
|
||||
MCU STM32F7xx STM32F767xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 41775
|
||||
|
||||
# default to all pins low to avoid ESD issues
|
||||
DEFAULTGPIO OUTPUT LOW PULLDOWN
|
||||
|
||||
FLASH_RESERVE_START_KB 32
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 UART7 UART5 USART1 UART4 USART2 USART6 USART3 OTG2
|
||||
|
||||
# default the 2nd interface to MAVLink2
|
||||
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
||||
|
||||
# now we define the pins that USB is connected on
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
PA9 VBUS INPUT
|
||||
|
||||
# these are the pins for SWD debugging with a STlinkv2 or black-magic probe
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# SPI1 - ICM20602
|
||||
PA5 SPI1_SCK SPI1
|
||||
PB4 SPI1_MISO SPI1
|
||||
PB5 SPI1_MOSI SPI1
|
||||
|
||||
# SPI2 - ICM42688
|
||||
PI1 SPI2_SCK SPI2
|
||||
PI2 SPI2_MISO SPI2
|
||||
PI3 SPI2_MOSI SPI2
|
||||
|
||||
# SPI5 - FRAM
|
||||
PF7 SPI5_SCK SPI5
|
||||
PF8 SPI5_MISO SPI5
|
||||
PF11 SPI5_MOSI SPI5
|
||||
|
||||
# SPI6 - BMI088 6DoF, disabled due to lack of DMA channels
|
||||
#PB3 SPI6_SCK SPI6
|
||||
#PA6 SPI6_MISO SPI6
|
||||
#PG14 SPI6_MOSI SPI6
|
||||
|
||||
# sensor CS
|
||||
PI9 ICM20602_CS CS
|
||||
PH5 ICM42688_CS CS
|
||||
PA15 BMI088_G_CS CS
|
||||
PI10 BMI088_A_CS CS
|
||||
PG7 FRAM_CS CS SPEED_VERYLOW
|
||||
|
||||
# fsync pins
|
||||
PA0 IMU_2_FSYNC INPUT FLOATING
|
||||
PA1 IMU_3_FSYNC INPUT FLOATING
|
||||
|
||||
# interrupt pins
|
||||
PF2 IMU_1_DRDY INPUT PULLDOWN
|
||||
PH12 IMU_2_DRDY INPUT PULLDOWN
|
||||
PG5 BARO_INT INPUT PULLDOWN
|
||||
PF3 SPARE_INT INPUT PULLDOWN
|
||||
PI6 IMU_3_ACCEL_INT INPUT PULLDOWN
|
||||
PI7 IMU_3_GYRO_INT INPUT PULLDOWN
|
||||
|
||||
# LSE crystal, unused
|
||||
PC14 LSE1 INPUT FLOATING
|
||||
PC15 LSE2 INPUT FLOATING
|
||||
|
||||
# HWID pins, unused
|
||||
PA4 HWID_DAC1 INPUT FLOATING
|
||||
PF4 HW_VER_SENS INPUT FLOATING
|
||||
PF5 HW_REV_SENS INPUT FLOATING
|
||||
PG0 HW_VR_DRIVE INPUT FLOATING
|
||||
|
||||
# security module, A71CH
|
||||
PH3 SEC_RESET INPUT PULLDOWN
|
||||
|
||||
|
||||
# I2C buses
|
||||
|
||||
# I2C1, EXT_GPS_I2C
|
||||
PB8 I2C1_SCL I2C1
|
||||
PB7 I2C1_SDA I2C1
|
||||
|
||||
# I2C2, DISPLAY_I2C
|
||||
PF1 I2C2_SCL I2C2
|
||||
PF0 I2C2_SDA I2C2
|
||||
|
||||
# I2C3, EXP_I2C
|
||||
PH7 I2C3_SCL I2C3
|
||||
PH8 I2C3_SDA I2C3
|
||||
|
||||
# I2C4, BMP388 BARO AND A71CH SEC MODULE (0x49)
|
||||
PF14 I2C4_SCL I2C4
|
||||
PF15 I2C4_SDA I2C4
|
||||
|
||||
# order of I2C buses
|
||||
I2C_ORDER I2C4 I2C3 I2C2 I2C1
|
||||
|
||||
define HAL_I2C_INTERNAL_MASK 1
|
||||
|
||||
# GPIOs
|
||||
PE3 EXC_GPIO_25 INPUT FLOATING GPIO(110)
|
||||
# PE4 EXC_GPIO_26 INPUT FLOATING GPIO(111)
|
||||
|
||||
# allow to have have a dedicated safety switch pin
|
||||
# on PE4
|
||||
PE4 SAFETY_IN INPUT PULLDOWN
|
||||
define HAL_HAVE_SAFETY_SWITCH 1
|
||||
define BOARD_SAFETY_ENABLE_DEFAULT 0
|
||||
|
||||
# start peripheral power off, then enable after init
|
||||
# this prevents a problem with radios that use RTS for
|
||||
# bootloader hold
|
||||
#PF12 nVDD_5V_HIPOWER_EN OUTPUT HIGH
|
||||
#PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH
|
||||
|
||||
#PG5 VDD_5V_RC_EN OUTPUT HIGH
|
||||
#PG6 VDD_5V_WIFI_EN OUTPUT HIGH
|
||||
PC13 VDD_3V3_SD_CARD_EN OUTPUT HIGH
|
||||
|
||||
# UARTs
|
||||
|
||||
# USART1 is EXT_GPS
|
||||
PB15 USART1_RX USART1 NODMA
|
||||
PB14 USART1_TX USART1
|
||||
|
||||
# USART2 is telem3, MSS_SPARE_4W
|
||||
PA3 USART2_RX USART2 NODMA
|
||||
PD5 USART2_TX USART2
|
||||
PD3 USART2_CTS USART2
|
||||
PD4 USART2_RTS USART2
|
||||
|
||||
# USART3, UART_2W_DEBUG
|
||||
PD9 USART3_RX USART3 NODMA
|
||||
PD8 USART3_TX USART3
|
||||
|
||||
# UART4 GPS2, EXP_UART_2W
|
||||
PH14 UART4_RX UART4 NODMA
|
||||
PH13 UART4_TX UART4
|
||||
|
||||
# UART5 Telem 2, MSS_UART_4W
|
||||
PD2 UART5_RX UART5
|
||||
PB9 UART5_TX UART5
|
||||
PC8 UART5_RTS UART5
|
||||
PC9 UART5_CTS UART5
|
||||
|
||||
# USART6, spektrum
|
||||
PC7 USART6_RX USART6 NODMA GPIO(74)
|
||||
PC6 USART6_TX USART6
|
||||
|
||||
# RC input. Support all serial protocols on both PPM and spektrum
|
||||
# ports. PPM protocol also supported on the PPM port
|
||||
PI5 TIM8_CH1 TIM8 RCININT PULLDOWN LOW
|
||||
|
||||
# setup for spektrum satellite bind
|
||||
define HAL_GPIO_SPEKTRUM_RC 74
|
||||
PH2 SPEKTRUM_PWR OUTPUT HIGH GPIO(73)
|
||||
define HAL_GPIO_SPEKTRUM_PWR 73
|
||||
define HAL_SPEKTRUM_PWR_ENABLED 1
|
||||
|
||||
# setup for RCIN on USUART6, will auto-baud for 100000 and 115200 and
|
||||
# auto-switch inversion as needed
|
||||
define HAL_SERIAL6_PROTOCOL 23
|
||||
define HAL_SERIAL6_BAUD 115200
|
||||
|
||||
# UART7 Telem 1, TELEM_UART_4W
|
||||
PE7 UART7_RX UART7
|
||||
PE8 UART7_TX UART7
|
||||
PE9 UART7_RTS UART7
|
||||
PE10 UART7_CTS UART7
|
||||
|
||||
# PWM AUX channels
|
||||
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
|
||||
PA10 TIM1_CH3 TIM1 PWM(2) GPIO(51)
|
||||
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
|
||||
PA8 TIM1_CH1 TIM1 PWM(4) GPIO(53)
|
||||
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
|
||||
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
|
||||
PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56)
|
||||
PD15 TIM4_CH4 TIM4 PWM(8) GPIO(57)
|
||||
|
||||
# PWM output for buzzer
|
||||
#PE5 TIM9_CH1 TIM9 GPIO(77) ALARM
|
||||
|
||||
define HAL_USE_ADC FALSE
|
||||
define HAL_DISABLE_ADC_DRIVER TRUE
|
||||
|
||||
# INA231 battery monitor
|
||||
define HAL_BATTMON_INA231_BUS 1
|
||||
define HAL_BATTMON_INA231_ADDR 0x44
|
||||
define HAL_BATT_MONITOR_DEFAULT 21
|
||||
|
||||
# on some units a LTC2946 is used
|
||||
define HAL_BATTMON_LTC2946_BUS 1
|
||||
define HAL_BATTMON_LTC2946_ADDR 0x6a
|
||||
|
||||
PC0 VDD_5V_SENS ADC1 SCALE(2) # ADC pin 10
|
||||
PC1 SCALED_V3V3 ADC1 SCALE(2)
|
||||
|
||||
define ANALOG_VCC_5V_PIN 10
|
||||
|
||||
# CAN bus
|
||||
PD0 CAN1_RX CAN1
|
||||
PD1 CAN1_TX CAN1
|
||||
PI11 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
#PHI11 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70)
|
||||
|
||||
# SPI devices
|
||||
SPIDEV icm42688 SPI2 DEVID1 ICM42688_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV icm20602 SPI1 DEVID2 ICM20602_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
|
||||
|
||||
# SPI6 disabled due to lack of DMA channels
|
||||
#SPIDEV bmi088_g SPI6 DEVID3 BMI088_G_CS MODE3 10*MHZ 10*MHZ
|
||||
#SPIDEV bmi088_a SPI6 DEVID4 BMI088_A_CS MODE3 10*MHZ 10*MHZ
|
||||
|
||||
# two IMUs enabled
|
||||
IMU Invensensev3 SPI:icm42688 ROTATION_YAW_180
|
||||
IMU Invensense SPI:icm20602 ROTATION_PITCH_180_YAW_90
|
||||
#IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_ROLL_180_YAW_90
|
||||
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 3
|
||||
|
||||
# one baro on I2C4
|
||||
BARO BMP388 I2C:0:0x76
|
||||
|
||||
# microSD support on SDMMC2
|
||||
PG9 SDMMC2_D0 SDMMC2
|
||||
PG10 SDMMC2_D1 SDMMC2
|
||||
PG11 SDMMC2_D2 SDMMC2
|
||||
PG12 SDMMC2_D3 SDMMC2
|
||||
PD6 SDMMC2_CK SDMMC2
|
||||
PD7 SDMMC2_CMD SDMMC2
|
||||
|
||||
define FATFS_HAL_DEVICE SDCD2
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
# red LED
|
||||
PB0 LED_RED OUTPUT OPENDRAIN GPIO(90)
|
||||
PB1 LED_GREEN OUTPUT OPENDRAIN GPIO(91)
|
||||
PA7 LED_BLUE OUTPUT OPENDRAIN GPIO(92)
|
||||
|
||||
# 2nd bank of LEDs
|
||||
PI0 LED_RED_2 OUTPUT OPENDRAIN LOW GPIO(93)
|
||||
PA2 LED_BLUE_2 OUTPUT OPENDRAIN LOW GPIO(94)
|
||||
PH11 LED_GREEN_2 OUTPUT OPENDRAIN LOW GPIO(95)
|
||||
|
||||
# setup for BoardLED2
|
||||
define HAL_GPIO_A_LED_PIN 90
|
||||
define HAL_GPIO_B_LED_PIN 92
|
||||
define HAL_GPIO_C_LED_PIN 91
|
||||
define HAL_GPIO_LED_ON 0
|
||||
|
||||
# enable RAMTROM parameter storage
|
||||
define HAL_STORAGE_SIZE 32768
|
||||
define HAL_WITH_RAMTRON 1
|
||||
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
||||
|
||||
DMA_PRIORITY SDMMC* ADC* SPI* TIM* UART*
|
||||
|
Loading…
Reference in New Issue
Block a user