mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
d35fff5186
this appears to be the root cause of the parameter resets on CubeOrange. We need to ensure the CS pin is not floating or random noise on the SPI bus for FRAM can cause the FRAM to become corrupt
132 lines
2.4 KiB
Plaintext
132 lines
2.4 KiB
Plaintext
# hw definition file for Zubax GNSS
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F105 STM32F105xC
|
|
|
|
define STM32F107_MCUCONF
|
|
|
|
FLASH_RESERVE_START_KB 0
|
|
FLASH_BOOTLOADER_LOAD_KB 34
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1005
|
|
|
|
# setup build for a peripheral firmware
|
|
env AP_PERIPH 1
|
|
|
|
define HAL_BOARD_AP_PERIPH_ZUBAXGNSS
|
|
|
|
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_ZubaxGNSS"
|
|
|
|
# use DNA
|
|
define HAL_CAN_DEFAULT_NODE_ID 0
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 16000000
|
|
|
|
define CH_CFG_ST_FREQUENCY 1000
|
|
|
|
FLASH_SIZE_KB 256
|
|
|
|
# reserve space for params
|
|
FLASH_RESERVE_END_KB 2
|
|
|
|
# reserve 256 bytes for comms between app and bootloader
|
|
RAM_RESERVE_START 256
|
|
|
|
# USART3 for debug
|
|
#STDOUT_SERIAL SD3
|
|
#STDOUT_BAUDRATE 115200
|
|
|
|
# USART3 for debug
|
|
PB10 USART3_TX USART3 SPEED_HIGH NODMA
|
|
PB11 USART3_RX USART3 SPEED_HIGH NODMA
|
|
|
|
# board voltage
|
|
STM32_VDD 330U
|
|
|
|
PB7 PERIPH_RESET OUTPUT HIGH
|
|
|
|
#PC1 HWID_BIT0 INPUT
|
|
#PC2 HWID_BIT1_INV INPUT
|
|
#PC3 HWID_BIT2 INPUT
|
|
|
|
PB3 LED_BOOTLOADER OUTPUT
|
|
PB5 LED_CAN1 OUTPUT
|
|
PB4 LED_CAN2 OUTPUT
|
|
define HAL_LED_ON 1
|
|
|
|
# don't enable DMA in UART driver
|
|
define HAL_UART_NODMA
|
|
|
|
# enable CAN support
|
|
PA11 CAN_RX CAN
|
|
PB9 CAN_TX CAN
|
|
define HAL_USE_CAN TRUE
|
|
define STM32_CAN_USE_CAN1 TRUE
|
|
|
|
# no I2C buses
|
|
# I2C_ORDER
|
|
|
|
define HAL_USE_ADC FALSE
|
|
define STM32_ADC_USE_ADC1 FALSE
|
|
define HAL_DISABLE_ADC_DRIVER TRUE
|
|
|
|
define HAL_NO_GPIO_IRQ
|
|
|
|
define CH_CFG_ST_TIMEDELTA 0
|
|
define SERIAL_BUFFERS_SIZE 512
|
|
define HAL_USE_EMPTY_IO TRUE
|
|
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 0x100
|
|
PROCESS_STACK 0x600
|
|
define HAL_DISABLE_LOOP_DELAY
|
|
|
|
define HAL_NO_ROMFS_SUPPORT
|
|
|
|
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 512
|
|
|
|
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_USE_EMPTY_STORAGE 1
|
|
|
|
define HAL_DEVICE_THREAD_STACK 768
|
|
|
|
define AP_PARAM_MAX_EMBEDDED_PARAM 0
|
|
|
|
# USART2 for GPS
|
|
PA2 USART2_TX USART2 SPEED_HIGH NODMA
|
|
PA3 USART2_RX USART2 SPEED_HIGH NODMA
|
|
|
|
UART_ORDER
|
|
|
|
define HAL_STORAGE_SIZE 800
|
|
|
|
# Add CS pins to ensure they are high in bootloader
|
|
PA15 BARO_CS CS
|
|
PD2 MAG_CS CS
|