HAL_ChibiOS: removed boilerplate lines from bootloaders

This commit is contained in:
Andrew Tridgell 2021-10-18 10:05:45 +11:00
parent 0378e1a879
commit 68146d541c
97 changed files with 2 additions and 467 deletions

View File

@ -35,9 +35,6 @@ PA14 JTCK-SWCLK SWD
PC13 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PA4 MPU6000_CS CS
PA15 FLASH_CS CS

View File

@ -39,9 +39,6 @@ PA14 JTCK-SWCLK SWD
PC13 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PA4 MPU6000_CS CS
PA15 FLASH_CS CS

View File

@ -57,18 +57,11 @@ define HAL_USE_EMPTY_IO TRUE
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
@ -78,8 +71,6 @@ define STM32_CAN_USE_CAN1 TRUE
define CAN_APP_NODE_NAME "org.ardupilot.birdcandy"
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
# make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600
@ -87,5 +78,3 @@ 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

View File

@ -41,9 +41,6 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
define BOOTLOADER_DEBUG SD7

View File

@ -41,9 +41,6 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
define BOOTLOADER_DEBUG SD7

View File

@ -59,18 +59,11 @@ define HAL_USE_EMPTY_IO TRUE
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
@ -80,8 +73,6 @@ define STM32_CAN_USE_CAN1 TRUE
define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps"
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
# make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600
@ -89,8 +80,6 @@ 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
PA4 MAG_CS CS

View File

@ -43,6 +43,3 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384

View File

@ -40,9 +40,6 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PC1 MAG_CS CS
PC2 MPU_CS CS
@ -61,10 +58,6 @@ PD1 CAN1_TX CAN1
PB6 CAN2_TX CAN2
PB12 CAN2_RX CAN2
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.CubeBlack-periph"

View File

@ -40,9 +40,6 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PC1 MAG_CS CS
PC2 MPU_CS CS
@ -61,10 +58,6 @@ PD1 CAN1_TX CAN1
PB6 CAN2_TX CAN2
PB12 CAN2_RX CAN2
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.CubeOrange-periph"

View File

@ -42,9 +42,6 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PC1 MAG_CS CS
PC2 MPU_CS CS

View File

@ -52,10 +52,6 @@ FLASH_RESERVE_START_KB 0
# start on 4th sector (1st sector for bootloader, 2 for extra storage)
FLASH_BOOTLOADER_LOAD_KB 96
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PC1 MAG_CS CS
PC2 MPU_CS CS

View File

@ -57,7 +57,6 @@ define HAL_LED_ON 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
PC2 MPU9250_CS CS

View File

@ -47,9 +47,6 @@ PA14 JTCK-SWCLK SWD
# pullup buzzer for no sound in bootloader
PE5 BUZZER OUTPUT LOW PULLDOWN
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PF10 MS5611_CS CS
PF2 ICM20689_CS CS SPEED_VERYLOW

View File

@ -18,10 +18,6 @@ FLASH_SIZE_KB 1024
# the location where the bootloader will put the firmware
FLASH_BOOTLOADER_LOAD_KB 64
define HAL_STORAGE_SIZE 15360
define STORAGE_FLASH_PAGE 1
# order of UARTs
SERIAL_ORDER OTG1 USART1 USART2 UART5

View File

@ -33,9 +33,6 @@ PD6 USART2_RX USART2
FLASH_USE_MAX_KB 16
FLASH_RESERVE_START_KB 0
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# location of application code
FLASH_BOOTLOADER_LOAD_KB 16

View File

@ -35,9 +35,6 @@ PA14 JTCK-SWCLK SWD
PC13 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PE4 MPU6000_CS CS
PA4 FLASH_CS CS

View File

@ -52,18 +52,10 @@ define HAL_USE_EMPTY_IO TRUE
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
@ -73,17 +65,11 @@ 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

View File

@ -19,9 +19,6 @@ env AP_PERIPH 1
STM32_ST_USE_TIMER 5
# enable watchdog
define HAL_WATCHDOG_ENABLED_DEFAULT true
# crystal frequency
OSCILLATOR_HZ 16000000
@ -110,14 +107,8 @@ 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
@ -133,8 +124,6 @@ define HAL_NO_MONITOR_THREAD
define HAL_MINIMIZE_FEATURES 0
define HAL_BUILD_AP_PERIPH
define HAL_DEVICE_THREAD_STACK 768
# we setup a small defaults.parm
@ -159,12 +148,6 @@ define BARO_MAX_INSTANCES 1
define HAL_PERIPH_GPS_PORT_DEFAULT 2
# 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
# listen for reboot command from uploader.py script
# undefine to disable. Use -1 to allow on all ports, otherwise serial number index defined in SERIAL_ORDER starting at 0
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0

View File

@ -45,22 +45,15 @@ define SERIAL_BUFFERS_SIZE 32
define HAL_USE_EMPTY_IO TRUE
define PORT_INT_REQUIRED_STACK 64
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 0x800
PROCESS_STACK 0x800
define HAL_DISABLE_LOOP_DELAY
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# enable CAN support
PB5 CAN2_RX CAN2
PB6 CAN2_TX CAN2
@ -90,11 +83,7 @@ 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
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.G4-ESC"

View File

@ -58,13 +58,6 @@ PA12 OTG_FS_DP OTG1
# order of UARTs (and USB)
SERIAL_ORDER OTG1 USART1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# QSPI Flash
PF8 QUADSPI_BK1_IO0 QUADSPI1
PF9 QUADSPI_BK1_IO1 QUADSPI1
@ -78,8 +71,6 @@ QSPIDEV mt25q QUADSPI1 MODE1 120*MHZ 24 8
PB13 VBUS INPUT OPENDRAIN
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.cubepilot.H757"
define BOOTLOADER_DEBUG SD1
define BOOTLOADER_DEBUG SD1

View File

@ -58,13 +58,6 @@ PA12 OTG_FS_DP OTG1
# order of UARTs (and USB)
SERIAL_ORDER OTG1 USART1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# QSPI Flash
PF8 QUADSPI_BK1_IO0 QUADSPI1
PF9 QUADSPI_BK1_IO1 QUADSPI1
@ -78,8 +71,6 @@ QSPIDEV mt25q QUADSPI1 MODE1 120*MHZ 24 8
PB13 VBUS INPUT OPENDRAIN
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.cubepilot.H757"
define BOOTLOADER_DEBUG SD1

View File

@ -13,7 +13,6 @@ env AP_PERIPH 1
FLASH_SIZE_KB 2048
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# the location where the bootloader will put the firmware
# the H743 has 128k sectors
@ -63,6 +62,3 @@ define HAL_LED_ON 0
PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1
PC7 SLEEPCAN OUTPUT PUSHPULL SPEED_LOW LOW
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384

View File

@ -57,17 +57,9 @@ PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
###########################
define PERIPH_FW TRUE
define USB_USE_WAIT TRUE
define HAL_USE_USB_MSD TRUE
define HAL_BUILD_AP_PERIPH
define HAL_DEVICE_THREAD_STACK 2048
#define AP_PARAM_MAX_EMBEDDED_PARAM 0
@ -82,9 +74,6 @@ define HAL_COMPASS_MAX_SENSORS 1
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_MAG
# use the app descriptor needed by MissionPlanner for CAN upload
env APP_DESCRIPTOR MissionPlanner
# Add MAVLink
env FORCE_MAVLINK_INCLUDE 1
@ -153,11 +142,7 @@ PH13 VDD_33V_SENS INPUT
# This defines some input pins, currently unused.
PB2 BOOT1 INPUT
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
# passthrough CAN1
define HAL_DEFAULT_CPORT 1

View File

@ -45,22 +45,15 @@ define SERIAL_BUFFERS_SIZE 32
define HAL_USE_EMPTY_IO TRUE
define PORT_INT_REQUIRED_STACK 64
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 0x800
PROCESS_STACK 0x800
define HAL_DISABLE_LOOP_DELAY
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# enable CAN support
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
@ -77,11 +70,7 @@ 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
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.Hitec-Airspeed"

View File

@ -58,20 +58,13 @@ define PORT_INT_REQUIRED_STACK 64
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
MAIN_STACK 0x800
PROCESS_STACK 0x800
define HAL_DISABLE_LOOP_DELAY
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# enable CAN support
PB8 CAN_RX CAN
PB9 CAN_TX CAN
@ -93,13 +86,9 @@ define HAL_BOOTLOADER_TIMEOUT 1000
PA5 STAY_IN_BOOTLOADER INPUT PULLUP
define HAL_STAY_IN_BOOTLOADER_VALUE 0
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# Add CS pins to ensure they are high in bootloader
PB1 MAG_CS CS
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.HitecMosaic"

View File

@ -57,18 +57,11 @@ define HAL_USE_EMPTY_IO TRUE
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
PA11 CAN1_RX CAN1
@ -81,8 +74,6 @@ PA4 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
define CAN_APP_NODE_NAME "org.ardupilot.HolybroGPS"
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
# make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600
@ -90,8 +81,6 @@ define BOOTLOADER_BAUDRATE 57600
# use a smaller bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 2500
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# Add CS pins to ensure they are high in bootloader
PA8 ACC_CS CS

View File

@ -31,10 +31,6 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360
# Add CS pins to ensure they are high in bootloader
PB14 MAX7456_CS CS
PB3 FLASH_CS CS

View File

@ -37,9 +37,6 @@ PD15 BUZZER OUTPUT LOW PULLDOWN
PA2 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Motors for esc init
PB1 PWMOUT1 OUTPUT LOW
PE9 PWMOUT2 OUTPUT LOW

View File

@ -36,9 +36,6 @@ PC13 BUZZER OUTPUT LOW PULLDOWN
PC2 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN

View File

@ -34,6 +34,3 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360

View File

@ -34,6 +34,3 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360

View File

@ -13,9 +13,6 @@ FLASH_RESERVE_START_KB 0
FLASH_SIZE_KB 1024
FLASH_BOOTLOADER_LOAD_KB 64
define HAL_STORAGE_SIZE 15360
define STORAGE_FLASH_PAGE 1
PA14 LED_BOOTLOADER OUTPUT LOW GPIO(0) # blue
PA13 LED_ACTIVITY OUTPUT LOW GPIO(1) # Green
define HAL_LED_ON 0

View File

@ -18,10 +18,6 @@ FLASH_SIZE_KB 1024
# the location where the bootloader will put the firmware
FLASH_BOOTLOADER_LOAD_KB 64
define HAL_STORAGE_SIZE 15360
define STORAGE_FLASH_PAGE 1
# order of UARTs
SERIAL_ORDER OTG1 USART1 USART3 UART4 UART5 USART6

View File

@ -30,10 +30,6 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360
# Add CS pins to ensure they are high in bootloader
PB10 MAX7456_CS CS
PC1 SDCARD_CS CS

View File

@ -36,10 +36,6 @@ PA14 JTCK-SWCLK SWD
PD10 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PC4 IMU1_CS CS
PB12 MAX7456_CS CS

View File

@ -5,9 +5,6 @@ include ../MatekH743/hwdef-bl.dat
PD0 CAN1_RX CAN1
PD1 CAN1_TX CAN1
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
env AP_PERIPH 1
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.MatekH743-periph"

View File

@ -40,9 +40,6 @@ PA14 JTCK-SWCLK SWD
PE3 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PC15 IMU1_CS CS
PB12 MAX7456_CS CS

View File

@ -42,6 +42,3 @@ PA14 JTCK-SWCLK SWD
PA2 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384

View File

@ -40,17 +40,11 @@ define HAL_NO_GPIO_IRQ
define HAL_USE_EMPTY_IO TRUE
define PORT_INT_REQUIRED_STACK 64
define HAL_USE_RTC FALSE
define DISABLE_SERIAL_ESC_COMM TRUE
define NO_DATAFLASH TRUE
define DMA_RESERVE_SIZE 0
define HAL_DISABLE_LOOP_DELAY
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# debugger support
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD

View File

@ -45,22 +45,15 @@ define SERIAL_BUFFERS_SIZE 32
define HAL_USE_EMPTY_IO TRUE
define PORT_INT_REQUIRED_STACK 64
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 0x800
PROCESS_STACK 0x800
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
@ -77,10 +70,6 @@ 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
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.Nucleo-L476"

View File

@ -51,22 +51,15 @@ define SERIAL_BUFFERS_SIZE 32
define HAL_USE_EMPTY_IO TRUE
define PORT_INT_REQUIRED_STACK 64
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 0x800
PROCESS_STACK 0x800
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
@ -83,10 +76,6 @@ 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
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.Nucleo-L496"

View File

@ -44,9 +44,6 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PA4 MPU_CS CS
PC7 BARO_CS CS

View File

@ -31,11 +31,6 @@ PA14 JTCK-SWCLK SWD
PA2 LED_BOOTLOADER OUTPUT HIGH
define HAL_LED_ON 0
define HAL_USE_EMPTY_STORAGE
define HAL_STORAGE_SIZE 16384
define STORAGE_FLASH_PAGE 1
# Add CS pins to ensure they are high in bootloader
PA4 MPU6000_CS CS
PA15 MPU6500_CS CS

View File

@ -32,10 +32,6 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360
# Add CS pins to ensure they are high in bootloader
PA4 MPU6000_CS CS
PB12 FLASH_CS CS

View File

@ -33,9 +33,6 @@ PA14 JTCK-SWCLK SWD
PD5 USART2_TX USART2
PD6 USART2_RX USART2
define HAL_STORAGE_SIZE 16384
define HAL_USE_EMPTY_STORAGE 1
# location of application code
FLASH_BOOTLOADER_LOAD_KB 64
@ -55,10 +52,6 @@ PD1 CAN1_TX CAN1
define CAN_APP_NODE_NAME "org.ardupilot.Pixracer-periph"
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
PB8 STAY_IN_BOOTLOADER INPUT FLOATING # if pulled low stay in bootloader

View File

@ -38,8 +38,6 @@ PD4 USART2_RTS USART2
PD5 USART2_TX USART2
PD6 USART2_RX USART2
define HAL_STORAGE_SIZE 16384
# location of application code
FLASH_BOOTLOADER_LOAD_KB 16

View File

@ -34,9 +34,6 @@ PA14 JTCK-SWCLK SWD
PC12 UART5_TX UART5 NODMA
PD2 UART5_RX UART5 NODMA
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PA4 ICM20689_CS CS
PE10 MAX7456_CS CS

View File

@ -32,9 +32,6 @@ PA14 JTCK-SWCLK SWD
PE0 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PA4 BARO_CS CS

View File

@ -52,22 +52,15 @@ define SERIAL_BUFFERS_SIZE 32
define HAL_USE_EMPTY_IO TRUE
define PORT_INT_REQUIRED_STACK 64
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 0x800
PROCESS_STACK 0x800
define HAL_DISABLE_LOOP_DELAY
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# enable CAN support
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
@ -85,11 +78,7 @@ 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
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-L431"

View File

@ -37,9 +37,6 @@ PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360
# Add CS pins to ensure they are high in bootloader
PA4 ICM20689_1_CS CS

View File

@ -49,6 +49,3 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384

View File

@ -51,6 +51,3 @@ define HAL_LED_ON 0
define HAL_CHIBIOS_ARCH_BRAINV51 1
define HAL_STORAGE_SIZE 16384
define HAL_USE_EMPTY_STORAGE 1

View File

@ -51,6 +51,3 @@ define HAL_LED_ON 0
define HAL_CHIBIOS_ARCH_BRAINV52 1
define HAL_STORAGE_SIZE 16384
define HAL_USE_EMPTY_STORAGE 1

View File

@ -52,6 +52,3 @@ define HAL_LED_ON 0
define HAL_CHIBIOS_ARCH_BRAINV54 1
define HAL_STORAGE_SIZE 16384
define HAL_USE_EMPTY_STORAGE 1

View File

@ -51,6 +51,3 @@ define HAL_LED_ON 0
define HAL_CHIBIOS_ARCH_COREV10 1
define HAL_STORAGE_SIZE 16384
define HAL_USE_EMPTY_STORAGE 1

View File

@ -51,6 +51,3 @@ define HAL_LED_ON 0
define HAL_CHIBIOS_ARCH_UBRAINV51 1
define HAL_STORAGE_SIZE 15360
define HAL_USE_EMPTY_STORAGE 1

View File

@ -18,8 +18,6 @@ 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
@ -31,8 +29,6 @@ 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
@ -84,19 +80,13 @@ 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
@ -107,9 +97,6 @@ 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
@ -120,8 +107,6 @@ PA3 USART2_RX USART2 SPEED_HIGH NODMA
SERIAL_ORDER
define HAL_STORAGE_SIZE 800
# Add CS pins to ensure they are high in bootloader
PA15 BARO_CS CS
PD2 MAG_CS CS

View File

@ -32,10 +32,6 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360
# Add CS pins to ensure they are high in bootloader
PA4 MPU6000_CS CS
PB3 FLASH_CS CS

View File

@ -35,10 +35,6 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360
# Add CS pins to ensure they are high in bootloader
PC12 E_CS0 CS
PB4 E_CS1 CS

View File

@ -2,6 +2,4 @@ include ../f103-periph/hwdef-bl.inc
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_adsb"
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0

View File

@ -2,6 +2,4 @@ include ../f103-periph/hwdef-bl.inc
define CAN_APP_NODE_NAME "org.ardupilot.f103_airspeed"
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0

View File

@ -1,6 +1,4 @@
include ../f103-periph/hwdef-bl.inc
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps"

View File

@ -1,6 +1,5 @@
include ../f103-periph/hwdef-bl.inc
# start with a fixed node ID so the board is usable without DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_HWESC"

View File

@ -2,6 +2,4 @@ include ../f103-periph/hwdef-bl.inc
define CAN_APP_NODE_NAME "org.ardupilot.f103Qiotek_Periph"
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0

View File

@ -2,7 +2,5 @@ include ../f103-periph/hwdef-bl.inc
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_rangefinder"
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0

View File

@ -1,6 +1,4 @@
include ../f103-periph/hwdef-bl.inc
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_trigger"

View File

@ -58,20 +58,13 @@ define PORT_INT_REQUIRED_STACK 64
#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 0x800
PROCESS_STACK 0x800
define HAL_DISABLE_LOOP_DELAY
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# enable CAN support
PA11 CAN_RX CAN
PA12 CAN_TX CAN
@ -91,7 +84,6 @@ define HAL_BOOTLOADER_TIMEOUT 1000
PB6 STAY_IN_BOOTLOADER INPUT FLOATING
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# Add CS pins to ensure they are high in bootloader
PB0 MAG_CS CS

View File

@ -1,6 +1,4 @@
include ../f303-periph/hwdef-bl.inc
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps"

View File

@ -1,5 +1,4 @@
include ../f303-periph/hwdef-bl.inc
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_HWESC"

View File

@ -1,6 +1,5 @@
include ../f303-periph/hwdef-bl.inc
# start as DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.mro_m10025"

View File

@ -4,6 +4,5 @@ include ../f303-periph/hwdef-bl.inc
# M10084
# start as DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "io.mrobotics.m10070_loc1_BL"

View File

@ -59,20 +59,13 @@ define SERIAL_BUFFERS_SIZE 32
define HAL_USE_EMPTY_IO TRUE
define PORT_INT_REQUIRED_STACK 64
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 0x800
PROCESS_STACK 0x800
define HAL_DISABLE_LOOP_DELAY
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# enable CAN support
PA11 CAN_RX CAN
PA12 CAN_TX CAN
@ -91,10 +84,6 @@ define HAL_BOOTLOADER_TIMEOUT 1000
# want to stay in the bootloader
PB6 STAY_IN_BOOTLOADER INPUT FLOATING
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.f303_MatekGPS"

View File

@ -1,6 +1,4 @@
include ../f303-periph/hwdef-bl.inc
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_PWM"

View File

@ -1,6 +1,4 @@
include ../f303-periph/hwdef-bl.inc
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_universal"

View File

@ -55,20 +55,12 @@ define SERIAL_BUFFERS_SIZE 32
define HAL_USE_EMPTY_IO TRUE
define PORT_INT_REQUIRED_STACK 64
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 0x800
PROCESS_STACK 0x800
define HAL_DISABLE_LOOP_DELAY
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# enable CAN support
PA11 CAN_RX CAN
PA12 CAN_TX CAN
@ -92,7 +84,6 @@ define HAL_BOOTLOADER_TIMEOUT 1000
PB6 STAY_IN_BOOTLOADER INPUT FLOATING
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# Add CS pins to ensure they are high in bootloader
PB0 MAG_CS CS

View File

@ -106,7 +106,6 @@ define IO_THD_WA_SIZE 512
define HAL_MINIMIZE_FEATURES 0
define HAL_BUILD_AP_PERIPH
# only one I2C bus
I2C_ORDER I2C1
@ -125,9 +124,6 @@ define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1
define RANGEFINDER_MAX_INSTANCES 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

View File

@ -16,9 +16,6 @@ FLASH_RESERVE_START_KB 0
FLASH_SIZE_KB 1024
FLASH_BOOTLOADER_LOAD_KB 64
define HAL_STORAGE_SIZE 15360
define STORAGE_FLASH_PAGE 1
PA14 LED_BOOTLOADER OUTPUT LOW GPIO(0) # blue
define HAL_LED_ON 0
@ -50,11 +47,8 @@ PB9 CAN1_TX CAN1
define HAL_USE_CAN1 TRUE
define STM32_CAN_USE_CAN1 TRUE
# define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.f405_MatekGPS"
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# Add CS pins to ensure they are high in bootloader
PA4 MPU_CS CS

View File

@ -72,7 +72,6 @@ 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

View File

@ -41,9 +41,6 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PF10 MS5611_CS CS
PF2 ICM20689_CS CS SPEED_VERYLOW

View File

@ -20,9 +20,6 @@ FLASH_RESERVE_START_KB 0
# the H743 has 128k sectors
FLASH_BOOTLOADER_LOAD_KB 128
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# only one I2C bus
I2C_ORDER I2C1

View File

@ -43,19 +43,12 @@ define HAL_NO_GPIO_IRQ
define HAL_USE_EMPTY_IO TRUE
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
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
@ -67,10 +60,4 @@ PA14 JTCK-SWCLK SWD
# use a small bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 1000
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.mRo-M10095"

View File

@ -50,9 +50,6 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PD7 BARO_CS CS
PD10 FRAM_CS CS SPEED_VERYLOW

View File

@ -52,9 +52,6 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PC2 ICM_20602_CS CS
PD7 BARO_CS CS

View File

@ -52,9 +52,6 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PC2 ICM_20602_CS CS
PD7 BARO_CS CS

View File

@ -53,9 +53,6 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PC2 ICM_20602_CS CS
PD7 BARO_CS CS

View File

@ -45,9 +45,6 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PB12 CS_ADIS16470 CS
PA15 CS_ICM40609D CS

View File

@ -53,9 +53,6 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PC2 ICM_20602_CS CS
PD7 BARO_CS CS

View File

@ -58,10 +58,6 @@ FLASH_RESERVE_START_KB 0
# start on 4th sector (1st sector for bootloader, 2 for extra storage)
FLASH_BOOTLOADER_LOAD_KB 96
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PC1 MAG_CS CS #Not Connected
PC2 MPU_CS CS #MPU9250

View File

@ -42,7 +42,6 @@ PD6 USART2_RX USART2
PA8 LED_BOOTLOADER OUTPUT
define HAL_LED_ON 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PB2 GYRO_CS CS

View File

@ -35,9 +35,6 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PC2 LPS22HB_CS CS
PC15 MPU6500_CS CS

View File

@ -34,9 +34,6 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 32768
# UARTs
# USART2 is telem3, MSS_SPARE_4W

View File

@ -33,10 +33,6 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360
# Add CS pins to ensure they are high in bootloader
PA4 MPU6000_CS CS
PB12 SDCARD_CS CS

View File

@ -32,10 +32,6 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360
# Add CS pins to ensure they are high in bootloader
PB12 FLASH_CS CS
PA4 MPU6000_CS CS #SPI1_NSS

View File

@ -33,10 +33,6 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360
# Add CS pins to ensure they are high in bootloader
PA4 MPU_CS CS
PB3 FLASH_CS CS

View File

@ -33,10 +33,6 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360
# Add CS pins to ensure they are high in bootloader
PA4 MPU_CS CS
PB3 FLASH_CS CS

View File

@ -33,9 +33,6 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360
# Add CS pins to ensure they are high in bootloader
PC4 MPU_CS CS

View File

@ -32,9 +32,6 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360
# Add CS pins to ensure they are high in bootloader
PB10 MAX7456_CS CS
PC0 FLASH_CS CS