mirror of https://github.com/ArduPilot/ardupilot
86 lines
1.9 KiB
Plaintext
86 lines
1.9 KiB
Plaintext
# hw definition file for processing by chibios_hwdef.py
|
|
# for bootloader for FMUv3 hardware (ie. for Pixhawk1, Pixhawk2 cube, XUAV2.1 etc)
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F4xx STM32F427xx
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 9
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 24000000
|
|
|
|
|
|
# ChibiOS system timer
|
|
STM32_ST_USE_TIMER 5
|
|
|
|
# flash size
|
|
FLASH_SIZE_KB 2048
|
|
|
|
# location of application code
|
|
FLASH_BOOTLOADER_LOAD_KB 16
|
|
|
|
# bootloader loads at start of flash
|
|
FLASH_RESERVE_START_KB 0
|
|
|
|
# USB setup
|
|
USB_STRING_MANUFACTURER "ArduPilot"
|
|
|
|
# baudrate to run bootloader at on uarts
|
|
define BOOTLOADER_BAUDRATE 115200
|
|
|
|
# uarts and USB to run bootloader protocol on
|
|
SERIAL_ORDER OTG1 USART2 USART3 UART7
|
|
|
|
# this is the pin that senses USB being connected. It is an input pin
|
|
# setup as OPENDRAIN
|
|
PA9 VBUS INPUT OPENDRAIN
|
|
|
|
# now we define the pins that USB is connected on
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
# these are the pins for SWD debugging with a STlinkv2 or black-magic probe
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# Another USART, this one for telem1
|
|
PD5 USART2_TX USART2
|
|
PD6 USART2_RX USART2
|
|
PD3 USART2_CTS USART2
|
|
PD4 USART2_RTS USART2
|
|
|
|
# the telem2 USART, also with RTS/CTS available
|
|
# USART3 serial3 telem2
|
|
PD8 USART3_TX USART3
|
|
PD9 USART3_RX USART3
|
|
PD11 USART3_CTS USART3
|
|
PD12 USART3_RTS USART3
|
|
|
|
# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters)
|
|
PE7 UART7_RX UART7
|
|
PE8 UART7_TX UART7
|
|
|
|
# define a LED
|
|
PE12 LED_BOOTLOADER OUTPUT
|
|
define HAL_LED_ON 1
|
|
|
|
# this adds a C define which sets up the ArduPilot architecture
|
|
# define. Any line starting with 'define' is copied literally as
|
|
# a #define in the hwdef.h header
|
|
define HAL_CHIBIOS_ARCH_FMUV3 1
|
|
|
|
# we need to tell HAL_ChibiOS/Storage.cpp how much storage is
|
|
# available (in bytes)
|
|
define HAL_STORAGE_SIZE 16384
|
|
|
|
# Add CS pins to ensure they are high in bootloader
|
|
PC1 MAG_CS CS
|
|
PC2 MPU_CS CS
|
|
PC13 GYRO_EXT_CS CS
|
|
PC14 BARO_EXT_CS CS
|
|
PC15 ACCEL_EXT_CS CS
|
|
PD7 BARO_CS CS
|
|
PE4 MPU_EXT_CS CS
|
|
PD10 FRAM_CS CS SPEED_VERYLOW
|