ardupilot/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat

172 lines
3.4 KiB
Plaintext

# hw definition file for processing by chibios_pins.py
# MCU class and specific type
# MCU class and specific type
MCU STM32F4xx STM32F412Rx
# bootloader starts firmware at 64k
FLASH_RESERVE_START_KB 64
# store parameters in pages 2 and 3
define STORAGE_FLASH_PAGE 2
define HAL_STORAGE_SIZE 8192
# board ID for firmware load
APJ_BOARD_ID 1001
# setup build for a peripheral firmware
env AP_PERIPH 1
STM32_ST_USE_TIMER 5
# enable watchdog
define HAL_WATCHDOG_ENABLED_DEFAULT true
# crystal frequency
OSCILLATOR_HZ 16000000
STM32_HSE_ENABLED TRUE
STM32_PLLM_VALUE 16
STM32_PLLN_VALUE 384
STM32_PLLP_VALUE 4
STM32_PLLQ_VALUE 8
STM32_PLLSRC STM32_PLLSRC_HSE
STM32_PREE1 STM32_PREE1_DIV1
STM32_PREE2 STM32_PREE2_DIV1
STM32_HPRE STM32_HPRE_DIV1
STM32_PPRE1 STM32_PPRE1_DIV2
STM32_PPRE2 STM32_PPRE2_DIV2
define CH_CFG_ST_FREQUENCY 1000000
# assume 512k flash part
FLASH_SIZE_KB 512
STDOUT_SERIAL SD1
STDOUT_BAUDRATE 57600
# board voltage
STM32_VDD 330U
# order of UARTs
UART_ORDER USART1 USART2
# a LED to flash
PB12 LED OUTPUT LOW
# USART1 for debug
PB6 USART1_TX USART1 NODMA
PB7 USART1_RX USART1 NODMA
define HAL_SERIAL0_BAUD_DEFAULT 57600
# USART2 for GPS
PA2 USART2_TX USART2 NODMA
PA3 USART2_RX USART2 NODMA
# SWD debugging
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# only one I2C bus in normal config
PB4 I2C3_SDA I2C3
PA8 I2C3_SCL I2C3
define HAL_USE_I2C TRUE
define STM32_I2C_USE_I2C3 TRUE
define HAL_I2C_CLEAR_ON_TIMEOUT 0
define HAL_I2C_INTERNAL_MASK 0
# only one I2C bus
I2C_ORDER I2C3
# IST compass
COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180_YAW_90
# BMP388 baro
BARO BMP388 I2C:0:0x76
# PWM output for buzzer
PB10 TIM2_CH3 TIM2 GPIO(77) LOW ALARM
# safety LED, active low
PB1 SAFE_LED OUTPUT HIGH
define SAFE_LED_ON 0
# safety button
PB3 SAFE_BUTTON INPUT PULLDOWN
# WS2812 LED
PB0 TIM3_CH3 TIM3 PWM(1)
define HAL_BARO_ALLOW_INIT_NO_BARO
define HAL_USE_ADC FALSE
define STM32_ADC_USE_ADC1 FALSE
define HAL_DISABLE_ADC_DRIVER TRUE
define HAL_NO_GPIO_IRQ
# avoid RCIN thread to save memory
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
# enable CAN support
PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1
PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
# start with a fixed node ID so the board is usable without DNA
define HAL_CAN_DEFAULT_NODE_ID 116
define CAN_APP_VERSION_MAJOR 1
define CAN_APP_VERSION_MINOR 0
define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps"
define CH_DBG_ENABLE_STACK_CHECK TRUE
define HAL_NO_GCS
define HAL_NO_LOGGING
define HAL_NO_MONITOR_THREAD
define HAL_MINIMIZE_FEATURES 0
define HAL_BUILD_AP_PERIPH
define HAL_DEVICE_THREAD_STACK 768
define AP_PARAM_MAX_EMBEDDED_PARAM 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
# GPS+MAG+BARO+Buzzer+NeoPixels
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_BUZZER
define HAL_PERIPH_NEOPIXEL_COUNT 8
define HAL_PERIPH_NEOPIXEL_CHAN 0
define AP_PERIPH_LED_BRIGHT_DEFAULT 50
# 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