mirror of https://github.com/ArduPilot/ardupilot
parent
a7ad2dc940
commit
20e10dc401
|
@ -12,6 +12,8 @@ STM32_ST_USE_TIMER 5
|
|||
FLASH_SIZE_KB 2048
|
||||
FLASH_RESERVE_START_KB 0
|
||||
FLASH_BOOTLOADER_LOAD_KB 16
|
||||
define HAL_USE_EMPTY_STORAGE 1
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
SERIAL_ORDER OTG1 UART5
|
||||
|
||||
|
@ -35,5 +37,5 @@ PB1 ICM42605_CS CS
|
|||
PB2 ICM20649_CS CS
|
||||
PA4 RM3100_CS CS
|
||||
PE10 MAX7456_CS CS
|
||||
PB12 FRAM_CS CS SPEED_VERYLOW
|
||||
PE15 FLASH_CS CS
|
||||
PB12 FRAM_CS CS SPEED_VERYLOW
|
||||
PE15 FLASH_CS CS
|
||||
|
|
|
@ -8,6 +8,7 @@ MCU STM32F4xx STM32F427xx
|
|||
APJ_BOARD_ID 1068
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
env OPTIMIZE -O2
|
||||
|
||||
|
@ -61,24 +62,22 @@ PC11 UART4_RX UART4 NODMA
|
|||
PC12 UART5_TX UART5 NODMA
|
||||
PD2 UART5_RX UART5 NODMA
|
||||
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
# CAN Busses
|
||||
# CAN Busses 1
|
||||
PD0 CAN1_RX CAN1
|
||||
PD1 CAN1_TX CAN1
|
||||
|
||||
# SPI1 for IMU OSD
|
||||
PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PA7 SPI1_MOSI SPI1
|
||||
PB0 ICM20689_CS CS
|
||||
PB1 ICM42605_CS CS
|
||||
PB2 ICM20649_CS CS
|
||||
PA4 RM3100_CS CS
|
||||
PE10 MAX7456_CS CS
|
||||
PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PA7 SPI1_MOSI SPI1
|
||||
PB0 ICM20689_CS CS
|
||||
PB1 ICM42605_CS CS
|
||||
PB2 ICM20649_CS CS
|
||||
PA4 RM3100_CS CS
|
||||
PE10 MAX7456_CS CS
|
||||
|
||||
# SPI bus for dataflash AND SD
|
||||
PB13 SPI2_SCK SPI2
|
||||
PB13 SPI2_SCK SPI2
|
||||
PB14 SPI2_MISO SPI2
|
||||
PB15 SPI2_MOSI SPI2
|
||||
|
||||
|
@ -90,13 +89,13 @@ PB3 SPI3_SCK SPI3
|
|||
PB4 SPI3_MISO SPI3
|
||||
PB5 SPI3_MOSI SPI3
|
||||
|
||||
SPIDEV icm20689 SPI1 DEVID1 ICM20689_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV icm42605 SPI1 DEVID2 ICM42605_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV icm20649 SPI1 DEVID3 ICM20649_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV rm3100 SPI1 DEVID4 RM3100_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV osd SPI1 DEVID5 MAX7456_CS MODE0 10*MHZ 10*MHZ
|
||||
SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
|
||||
SPIDEV sdcard SPI2 DEVID2 FLASH_CS MODE0 1*MHZ 8*MHZ
|
||||
SPIDEV icm20689 SPI1 DEVID1 ICM20689_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV icm42605 SPI1 DEVID2 ICM42605_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV icm20649 SPI1 DEVID3 ICM20649_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV rm3100 SPI1 DEVID4 RM3100_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV osd SPI1 DEVID5 MAX7456_CS MODE0 10*MHZ 10*MHZ
|
||||
SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
|
||||
SPIDEV sdcard SPI2 DEVID2 FLASH_CS MODE0 1*MHZ 8*MHZ
|
||||
|
||||
# Three IMUs
|
||||
IMU Invensense SPI:icm20689 ROTATION_NONE
|
||||
|
@ -123,33 +122,33 @@ define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
|||
|
||||
# define the order that I2C buses
|
||||
I2C_ORDER I2C1 I2C2
|
||||
PB8 I2C1_SCL I2C1
|
||||
PB9 I2C1_SDA I2C1
|
||||
PB8 I2C1_SCL I2C1
|
||||
PB9 I2C1_SDA I2C1
|
||||
PB10 I2C2_SCL I2C2
|
||||
PB11 I2C2_SDA I2C2
|
||||
|
||||
define HAL_I2C_INTERNAL_MASK 0
|
||||
|
||||
# PWM out pins
|
||||
PA0 TIM2_CH1 TIM2 PWM(1) GPIO(50)
|
||||
PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51)
|
||||
PA2 TIM2_CH3 TIM2 PWM(3) GPIO(52)
|
||||
PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53)
|
||||
PE9 TIM1_CH1 TIM1 PWM(5) GPIO(54)
|
||||
PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55)
|
||||
PE13 TIM1_CH3 TIM1 PWM(7) GPIO(56)
|
||||
PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57)
|
||||
PA0 TIM2_CH1 TIM2 PWM(1) GPIO(50)
|
||||
PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51)
|
||||
PA2 TIM2_CH3 TIM2 PWM(3) GPIO(52)
|
||||
PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53)
|
||||
PE9 TIM1_CH1 TIM1 PWM(5) GPIO(54)
|
||||
PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55)
|
||||
PE13 TIM1_CH3 TIM1 PWM(7) GPIO(56)
|
||||
PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57)
|
||||
PD12 TIM4_CH1 TIM4 PWM(9) GPIO(58)
|
||||
PD13 TIM4_CH2 TIM4 PWM(10) GPIO(59)
|
||||
PD14 TIM4_CH3 TIM4 PWM(11) GPIO(60)
|
||||
PD15 TIM4_CH4 TIM4 PWM(12) GPIO(61)
|
||||
PC6 TIM3_CH1 TIM3 PWM(13) GPIO(62) NODMA
|
||||
PC8 TIM3_CH3 TIM3 PWM(14) GPIO(63) NODMA
|
||||
PC9 TIM3_CH4 TIM3 PWM(15) GPIO(64) NODMA
|
||||
PD13 TIM4_CH2 TIM4 PWM(10) GPIO(59)
|
||||
PD14 TIM4_CH3 TIM4 PWM(11) GPIO(60)
|
||||
PD15 TIM4_CH4 TIM4 PWM(12) GPIO(61)
|
||||
PC7 TIM3_CH2 TIM3 PWM(13) GPIO(62) NODMA
|
||||
PC8 TIM3_CH3 TIM3 PWM(14) GPIO(63) NODMA
|
||||
PC9 TIM3_CH4 TIM3 PWM(15) GPIO(64) NODMA
|
||||
|
||||
PC15 EXTERN_GPIO1 OUTPUT GPIO(1)
|
||||
PC14 EXTERN_GPIO2 OUTPUT GPIO(2)
|
||||
PC13 EXTERN_GPIO3 OUTPUT GPIO(3)
|
||||
PC15 EXTERN_GPIO1 OUTPUT GPIO(1)
|
||||
PC14 EXTERN_GPIO2 OUTPUT GPIO(2)
|
||||
PC13 EXTERN_GPIO3 OUTPUT GPIO(3)
|
||||
PE6 EXTERN_GPIO4 OUTPUT GPIO(4)
|
||||
PE4 EXTERN_GPIO5 OUTPUT GPIO(5)
|
||||
define RELAY1_PIN_DEFAULT 1
|
||||
|
@ -159,7 +158,7 @@ define RELAY4_PIN_DEFAULT 4
|
|||
define RELAY5_PIN_DEFAULT 5
|
||||
|
||||
# also USART6_RX for serial RC
|
||||
PC7 TIM8_CH2 TIM8 RCIN PULLDOWN LOW DMA_CH0
|
||||
PC6 TIM8_CH1 TIM8 RCININT PULLDOWN LOW DMA_CH0
|
||||
|
||||
# LED setup is similar to PixRacer
|
||||
define HAL_HAVE_PIXRACER_LED
|
||||
|
|
Loading…
Reference in New Issue