mirror of https://github.com/ArduPilot/ardupilot
130 lines
2.8 KiB
Plaintext
130 lines
2.8 KiB
Plaintext
# MCU class and specific type
|
|
MCU STM32F4xx STM32F407xx
|
|
|
|
FLASH_RESERVE_START_KB 64
|
|
FLASH_SIZE_KB 512
|
|
|
|
define HAL_STORAGE_SIZE 15360
|
|
STORAGE_FLASH_PAGE 2
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 6000
|
|
|
|
env AP_PERIPH 1
|
|
|
|
define CAN_APP_NODE_NAME "sw-spar-f407"
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 8000000
|
|
|
|
# we need tim2 for PWM
|
|
STM32_ST_USE_TIMER 5
|
|
|
|
# activity led
|
|
PC8 LED OUTPUT LOW
|
|
define HAL_LED_ON 1
|
|
|
|
# JTAG
|
|
#PA13 JTMS-SWDIO SWD
|
|
#PA14 JTCK-SWCLK SWD
|
|
|
|
# ECU - not currently used, must be enabled for CAN2 to work
|
|
PD0 CAN1_RX CAN1
|
|
PD1 CAN1_TX CAN1
|
|
PD2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW HIGH
|
|
|
|
# avionics can
|
|
PB5 CAN2_RX CAN2
|
|
PB6 CAN2_TX CAN2
|
|
PB7 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
|
|
|
# we don't actually need/use CAN mirroring, but it *can* make a very handy debug port
|
|
# define HAL_PERIPH_CAN_MIRROR 1
|
|
|
|
# ---------------------- UARTs ---------------------------
|
|
# | efi | gps | lidar |
|
|
SERIAL_ORDER USART1 USART2 USART3
|
|
|
|
# USART1 efi
|
|
PA9 USART1_TX USART1 SPEED_HIGH DMA
|
|
PA10 USART1_RX USART1 SPEED_HIGH DMA
|
|
|
|
# USART2 gps
|
|
PD5 USART2_TX USART2 SPEED_HIGH DMA
|
|
PD6 USART2_RX USART2 SPEED_HIGH DMA
|
|
|
|
# USART3 lidar
|
|
PB10 USART3_TX USART3 SPEED_HIGH DMA
|
|
PB11 USART3_RX USART3 SPEED_HIGH DMA
|
|
|
|
# throttle pwm
|
|
define HAL_PERIPH_ENABLE_RC_OUT
|
|
PA15 TIM2_CH1 TIM2 PWM(1)
|
|
|
|
# i2c
|
|
I2C_ORDER I2C3 I2C1
|
|
define STM32_I2C_USE_I2C1 TRUE
|
|
define STM32_I2C_USE_I2C3 TRUE
|
|
define HAL_I2C_CLEAR_ON_TIMEOUT 0
|
|
define HAL_I2C_INTERNAL_MASK 0
|
|
|
|
# gps/aux port
|
|
PB8 I2C1_SCL I2C1
|
|
PB9 I2C1_SDA I2C1
|
|
|
|
# internal mag
|
|
PA8 I2C3_SCL I2C3
|
|
PC9 I2C3_SDA I2C3
|
|
|
|
# EFI
|
|
define AP_PERIPH_EFI_PORT_DEFAULT 0
|
|
define HAL_PERIPH_ENABLE_EFI 1
|
|
define HAL_EFI_ENABLED 1
|
|
define HAL_PERIPH_EFI_BAUDRATE_DEFAULT 115200
|
|
|
|
# GPS
|
|
define HAL_PERIPH_ENABLE_GPS
|
|
define HAL_PERIPH_GPS_PORT_DEFAULT 1
|
|
define GPS_MAX_RATE_MS 200
|
|
|
|
define GPS_MAX_RECEIVERS 1
|
|
define GPS_MAX_INSTANCES 1
|
|
|
|
# rangefinder
|
|
define HAL_PERIPH_ENABLE_RANGEFINDER 2
|
|
define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 2
|
|
|
|
# compass
|
|
define HAL_PERIPH_ENABLE_MAG
|
|
define HAL_COMPASS_MAX_SENSORS 2
|
|
|
|
COMPASS MMC3416 I2C:0:0x30 false ROTATION_NONE
|
|
|
|
# expected aux compass, unclear if these need to be listed
|
|
COMPASS RM3100 I2C:1:0x20 false ROTATION_NONE
|
|
COMPASS RM3100 I2C:1:0x21 false ROTATION_NONE
|
|
COMPASS RM3100 I2C:1:0x22 false ROTATION_NONE
|
|
COMPASS RM3100 I2C:1:0x23 false ROTATION_NONE
|
|
|
|
# battery
|
|
define HAL_PERIPH_ENABLE_BATTERY
|
|
define HAL_PERIPH_BATTERY_SKIP_NAME # don't waste bandwidth on static names
|
|
|
|
define HAL_USE_ADC TRUE
|
|
define STM32_ADC_USE_ADC1 TRUE
|
|
|
|
# fuel tank
|
|
PB0 BATT3_VOLTAGE_SENS ADC1 SCALE(1) ANALOG(1)
|
|
# 12V in
|
|
PA4 BATT_VOLTAGE_SENS ADC1 SCALE(1) ANALOG(2)
|
|
# 5V in
|
|
PA5 BATT2_VOLTAGE_SENS ADC1 SCALE(1) ANALOG(3)
|
|
|
|
# don't build on firmware.ardupilot.org
|
|
AUTOBUILD_TARGETS None
|
|
|
|
define HAL_SERIAL_ESC_COMM_ENABLED 1
|
|
define HAL_RCIN_THREAD_ENABLED 1
|
|
define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1
|
|
define HAL_MONITOR_THREAD_ENABLED 1
|