ardupilot/libraries/AP_HAL_ChibiOS/hwdef/cube-red/hwdef.dat

246 lines
4.4 KiB
Plaintext
Raw Normal View History

2018-01-24 00:34:03 -04:00
# hw definition file for processing by chibios_hwdef.py
# for ProfiCNC/Hex CUBE RED hardware
# MCU class and specific type
MCU STM32F7xx STM32F769xx
# board ID for firmware load
APJ_BOARD_ID 9
# crystal frequency
OSCILLATOR_HZ 24000000
# board voltage
STM32_VDD 330U
# flash size
FLASH_SIZE_KB 2048
# serial port for stdout
STDOUT_SERIAL SD7
STDOUT_BAUDRATE 57600
# USB setup
USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE
USB_PRODUCT 0x1002
USB_STRING_MANUFACTURER "Hex Technology Limited"
USB_STRING_PRODUCT "ProfiCNC CUBE F7 FMU"
USB_STRING_SERIAL "%SERIAL%"
2018-01-24 00:34:03 -04:00
# order of I2C buses
I2C_ORDER I2C2 I2C1
# order of UARTs (and USB)
UART_ORDER OTG1 UART4 USART2 USART3 UART8
# UART for IOMCU
IOMCU_UART USART6
# UART4 serial GPS
PA0 UART4_TX UART4
PA1 UART4_RX UART4
PA2 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PA3 BATT_CURRENT_SENS ADC1 SCALE(1)
PA4 VDD_5V_SENS ADC1 SCALE(2)
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
PA8 CAN3_RX CAN3
PA9 VBUS INPUT OPENDRAIN
PA10 IO-debug-console
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
PA15 CAN3_TX CAN3
PB0 EXTERN_GPIO1 OUTPUT GPIO(1)
PB1 EXTERN_GPIO2 OUTPUT GPIO(2)
PB2 BOOT1 INPUT
PB3 FMU_SW0 INPUT
PB4 PWM_VOLT_SELECT OUTPUT LOW
PB5 SPI6_MOSI SPI6
PB6 CAN2_TX CAN2
#PB7
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2
PB12 CAN2_RX CAN2
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
PC0 HW_VERSION_SENSE INPUT
PC1 HW_REV_SENSE INPUT
#PC2
#PC3
#PC4
#PC5
# USART6 to IO
PC6 USART6_TX USART6
PC7 USART6_RX USART6
PC8 SDIO_D0 SDIO
PC9 SDIO_D1 SDIO
PC10 SDIO_D2 SDIO
PC11 SDIO_D3 SDIO
PC12 SDIO_CK SDIO
PC13 GYRO_EXT_CS CS
PC14 32KHz_IN
PC15 32KHz_OUT
PD0 CAN1_RX CAN1
PD1 CAN1_TX CAN1
PD2 SDIO_CMD SDIO
# USART2 serial2 telem1
PD3 USART2_CTS USART2
PD4 USART2_RTS USART2
PD5 USART2_TX USART2
PD6 USART2_RX USART2
PD7 BARO_CS CS
# USART3 serial3 telem2
PD8 USART3_TX USART3
PD9 USART3_RX USART3
PD10 FRAM_CS CS
PD11 USART3_CTS USART3
PD12 USART3_RTS USART3
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
PD15 MPU_DRDY INPUT
# UART8 serial4 GPS2
PE0 UART8_RX UART8
PE1 UART8_TX UART8
PE2 SPI4_SCK SPI4
PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH
PE4 ICM20948_CS CS
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4
# UART7 debug console
PE7 UART7_RX UART7
PE8 UART7_TX UART7
PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53)
#PE10
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
PE12 FMU_LED_AMBER OUTPUT GPIO(0)
PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51)
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
PE15 VDD_5V_PERIPH_OC INPUT
#PF0
#PF1
PF2 ICM20649_CS CS
PF3 FMU_AUX_POWER ADC1 SCALE(1)
PF4 FMU_AUX_ADC2 ADC1 SCALE(1)
PF5 PRESSURE_SENS ADC1 SCALE(1)
#PF6
#PF7
#PF8
#PF9
PF10 SPI4_MS5611_CS CS
PF11 SPI4_SPARE_CS CS
#PF12
PF13 VDD_5V_HIPOWER_OC
#PF14
#PF15
#PG0
PG1 VDD_BRICK_VALID INPUT
PG2 VBUS_VALID INPUT
PG3 VDD_BACKUP_VALID INPUT
PG4 VDD_5V_PERIPH_EN OUTPUT LOW
#PG5
#PG6
#PG7
PG8 SPI6_CS CS
#PG9
#PG10
PG11 SPI6_CS2 CS
PG12 SPI6_MISO SPI6
PG13 SPI6_SCK SPI6
#PG14
#PG15
#PH0 OSC_IN 24MHz
#PH1 OSC_OUT 24MHz
PH2 HW_VER_DRIVE OUTPUT HIGH
PH3 HW_REV_DRIVE OUTPUT HIGH
#PH4
#PH5
#PH6
#PH7
#PH8
PH9 ALARM
#PH10
#PH11
#PH12
#PH13
#PH14
#PH15
#PI0
#PI1
#PI2
#PI3
#PI4
PI5 PPM_IN
#PI6
#PI7
#PI8
#PI9
#PI10
#PI11
# SPI device table. The DEVID values are chosen to match the PX4 port
# of ArduPilot so users don't need to re-do their accel and compass calibrations
# when moving to ChibiOS
#sensors on Main FMU board
SPIDEV ms5611 SPI1 DEVID3 SPI1_MS5611_CS MODE3 20*MHZ 20*MHZ
SPIDEV ICM20649 SPI1 DEVID ICM20649_CS MODE3 1*MHZ 8*MHZ
#Sensors on the isolated IMU Board
SPIDEV ICM20602 SPI4 DEVID ICM20602_CS MODE3 1*MHZ 8*MHZ
SPIDEV ms5611_ext SPI4 DEVID2 SPI4_MS5611_CS MODE3 20*MHZ 20*MHZ
SPIDEV ICM20948 SPI4 DEVID ICM20948_CS MODE3 1*MHZ 8*MHZ
#FRAM
SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
#Spare CS Pins for external SPI devices (SPI6)
SPIDEV EXTERNAL_DEV1 SPI6 DEVID SPI6_CS MODE0 2*MHZ 2*MHZ
SPIDEV EXTERNAL_DEV2 SPI6 DEVID SPI6_CS2 MODE1 2*MHZ 2*MHZ
define HAL_CHIBIOS_ARCH_CUBE_RED 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 16384
# fallback storage location is flash if no FRAM fitted
define STORAGE_FLASH_PAGE 22
# enable RAMTROM parameter storage
define HAL_WITH_RAMTRON 1
# Cube Red has an IMU header
define HAL_HAVE_IMU_HEATER 1
# enable FAT filesystem
define HAL_OS_FATFS_IO 1