mirror of https://github.com/ArduPilot/ardupilot
150 lines
3.0 KiB
Plaintext
150 lines
3.0 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F103 STM32F103xB
|
|
|
|
# bootloader starts firmware at 25k
|
|
FLASH_RESERVE_START_KB 25
|
|
|
|
# store parameters in pages 23 and 24
|
|
define STORAGE_FLASH_PAGE 23
|
|
define HAL_STORAGE_SIZE 800
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1000
|
|
|
|
# setup build for a peripheral firmware
|
|
env AP_PERIPH 1
|
|
|
|
# enable watchdog
|
|
define HAL_WATCHDOG_ENABLED_DEFAULT true
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 8000000
|
|
|
|
define CH_CFG_ST_FREQUENCY 1000
|
|
|
|
# assume the 128k flash part for now
|
|
FLASH_SIZE_KB 128
|
|
|
|
# board voltage
|
|
STM32_VDD 330U
|
|
|
|
# order of UARTs
|
|
UART_ORDER USART2 USART1
|
|
|
|
# a LED to flash
|
|
PA4 LED OUTPUT LOW
|
|
|
|
# USART1, connected to GPS
|
|
PA9 USART1_TX USART1 SPEED_HIGH NODMA
|
|
PA10 USART1_RX USART1 SPEED_HIGH NODMA
|
|
|
|
# USART2 for debug
|
|
PA2 USART2_TX USART2 SPEED_HIGH NODMA
|
|
PA3 USART2_RX USART2 SPEED_HIGH NODMA
|
|
|
|
define HAL_UART_NODMA
|
|
|
|
# only one I2C bus in normal config
|
|
PB6 I2C1_SCL I2C1
|
|
PB7 I2C1_SDA I2C1
|
|
|
|
PB0 MAG_CS CS
|
|
|
|
# spi bus for compass
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
|
|
SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ
|
|
|
|
# analog input
|
|
# PA5 VIN5 ADC1
|
|
define HAL_USE_ADC TRUE
|
|
define STM32_ADC_USE_ADC1 TRUE
|
|
define HAL_DISABLE_ADC_DRIVER TRUE
|
|
|
|
define HAL_NO_GPIO_IRQ
|
|
define CH_CFG_ST_TIMEDELTA 0
|
|
#define CH_CFG_USE_DYNAMIC FALSE
|
|
define SERIAL_BUFFERS_SIZE 512
|
|
define PORT_INT_REQUIRED_STACK 64
|
|
|
|
# avoid timer and RCIN threads to save memory
|
|
define HAL_NO_TIMER_THREAD
|
|
define HAL_NO_RCIN_THREAD
|
|
|
|
#defined to turn off undef warnings
|
|
define __FPU_PRESENT 0
|
|
|
|
define HAL_USE_RTC FALSE
|
|
define DISABLE_SERIAL_ESC_COMM TRUE
|
|
define NO_DATAFLASH TRUE
|
|
|
|
define DMA_RESERVE_SIZE 0
|
|
|
|
define PERIPH_FW TRUE
|
|
|
|
# MAIN_STACK is stack of initial thread
|
|
MAIN_STACK 0x80
|
|
|
|
# PROCESS_STACK controls stack for main thread
|
|
PROCESS_STACK 0x600
|
|
define HAL_DISABLE_LOOP_DELAY
|
|
|
|
# enable CAN support
|
|
PA11 CAN_RX CAN
|
|
PA12 CAN_TX CAN
|
|
define HAL_USE_CAN TRUE
|
|
define STM32_CAN_USE_CAN1 TRUE
|
|
|
|
define HAL_USE_I2C TRUE
|
|
define STM32_I2C_USE_I2C1 TRUE
|
|
|
|
define HAL_UART_MIN_TX_SIZE 256
|
|
define HAL_UART_MIN_RX_SIZE 128
|
|
|
|
define HAL_UART_STACK_SIZE 256
|
|
define STORAGE_THD_WA_SIZE 256
|
|
define IO_THD_WA_SIZE 256
|
|
|
|
define HAL_NO_GCS
|
|
define HAL_NO_LOGGING
|
|
define HAL_NO_MONITOR_THREAD
|
|
|
|
define HAL_MINIMIZE_FEATURES 0
|
|
|
|
define HAL_BUILD_AP_PERIPH
|
|
|
|
# only one I2C bus
|
|
I2C_ORDER I2C1
|
|
|
|
COMPASS RM3100 SPI:rm3100 false ROTATION_NONE
|
|
|
|
define HAL_I2C_CLEAR_ON_TIMEOUT 0
|
|
|
|
define HAL_DEVICE_THREAD_STACK 256
|
|
|
|
define AP_PARAM_MAX_EMBEDDED_PARAM 0
|
|
|
|
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
|
define HAL_I2C_INTERNAL_MASK 0
|
|
|
|
# disable dual GPS and GPS blending to save flash space
|
|
define GPS_MAX_RECEIVERS 1
|
|
define GPS_MAX_INSTANCES 1
|
|
define HAL_COMPASS_MAX_SENSORS 1
|
|
|
|
# use the app descriptor needed by MissionPlanner for CAN upload
|
|
env APP_DESCRIPTOR MissionPlanner
|
|
|
|
# reserve 256 bytes for comms between app and bootloader
|
|
RAM_RESERVE_START 256
|
|
|
|
# define CH_DBG_ENABLE_STACK_CHECK TRUE
|
|
|
|
# keep ROMFS uncompressed as we don't have enough RAM
|
|
# to uncompress the bootloader at runtime
|
|
env ROMFS_UNCOMPRESSED True
|