ardupilot/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef-bl.dat

90 lines
1.9 KiB
Plaintext

# hw definition file for processing by chibios_pins.py
# MCU class and specific type
MCU STM32F7xx STM32F732xx
FLASH_RESERVE_START_KB 0
# two sectors for bootloader, two for storage
FLASH_BOOTLOADER_LOAD_KB 64
# board ID for firmware load
APJ_BOARD_ID 1028
# setup build for a peripheral firmware
env AP_PERIPH 1
# crystal frequency
OSCILLATOR_HZ 16000000
# assume 512k flash part
FLASH_SIZE_KB 512
# order of UARTs
SERIAL_ORDER OTG1
PC7 USB_RESET_N OUTPUT PUSHPULL HIGH
# use safety button to stay in bootloader
PC14 STAY_IN_BOOTLOADER INPUT PULLDOWN
define HAL_STAY_IN_BOOTLOADER_VALUE 1
PA6 LED_BOOTLOADER OUTPUT HIGH
define HAL_LED_ON 0
# 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
define HAL_USE_SERIAL FALSE
define STM32_SERIAL_USE_USART1 FALSE
define STM32_SERIAL_USE_USART2 FALSE
define STM32_SERIAL_USE_USART3 FALSE
define HAL_NO_GPIO_IRQ
define HAL_USE_EMPTY_IO TRUE
# avoid timer and RCIN threads to save memory
define HAL_NO_TIMER_THREAD
define HAL_NO_RCIN_THREAD
define HAL_USE_RTC FALSE
define DISABLE_SERIAL_ESC_COMM TRUE
define NO_DATAFLASH TRUE
define DMA_RESERVE_SIZE 0
define PERIPH_FW TRUE
define HAL_DISABLE_LOOP_DELAY
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# enable CAN support
PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
define CAN_APP_NODE_NAME "org.ardupilot.FreeflyRTK"
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
# make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600
# use a small bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 1000
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# Add CS pins to ensure they are high in bootloader
PA15 IMU_CS CS