hwdef: remove HAL_BOARD_LOG_DIRECTORY and HAL_BOARD_TERRAIN_DIRECTORY defaults

these are now defaulted in chibios_hwdef.py
This commit is contained in:
Peter Barker 2023-07-14 12:23:26 +10:00 committed by Randy Mackay
parent 092afa54a9
commit 338a4d6b38
76 changed files with 2 additions and 224 deletions

View File

@ -250,7 +250,4 @@ define FATFS_HAL_DEVICE SDCD2
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin

View File

@ -314,9 +314,6 @@ DMA_PRIORITY SDMMC* USART6* ADC* UART* USART* SPI* TIM*
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin
# enable DFU reboot for installing bootloader

View File

@ -147,8 +147,6 @@ SPIDEV osd SPI2 DEVID1 AT7456E_CS MODE0 10*MHZ 10*MHZ
# filesystem setup on sdcard
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# setup for OSD
define OSD_ENABLED 1

View File

@ -300,9 +300,6 @@ PE10 SAFETY_IN INPUT PULLDOWN
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
DMA_PRIORITY ADC* SPI1* TIM*UP*
DMA_NOSHARE SPI1* TIM*UP*

View File

@ -310,9 +310,6 @@ PE10 SAFETY_IN INPUT PULLDOWN
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
DMA_PRIORITY ADC* SPI1* TIM*UP*
DMA_NOSHARE SPI1* TIM*UP*

View File

@ -284,10 +284,6 @@ define HAL_CHIBIOS_ARCH_FMUV3 1
define BOARD_TYPE_DEFAULT 3
# Nnow some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 1

View File

@ -30,10 +30,6 @@ FLASH_BOOTLOADER_LOAD_KB 128
define HAL_LED_ON 0
# Nnow some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# Enable FAT filesystem support (needs a microSD defined via SDMMC).
define HAL_OS_FATFS_IO 1

View File

@ -423,10 +423,6 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES
# a #define in the hwdef.h header
define HAL_CHIBIOS_ARCH_FMUV3 1
# now some defines for logging and terrain data files
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# we need to tell HAL_ChibiOS/Storage.cpp how much storage is
# available (in bytes)
define HAL_STORAGE_SIZE 32768

View File

@ -122,8 +122,6 @@ define ALLOW_ARM_NO_COMPASS
define HAL_BARO_ALLOW_INIT_NO_BARO
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define BOARD_PWM_COUNT_DEFAULT 4

View File

@ -223,9 +223,6 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_CHIBIOS_ARCH_FMUV4PRO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 16384
define HAL_WITH_RAMTRON 1

View File

@ -322,9 +322,6 @@ define HAL_COMPASS_AUTO_ROT_DEFAULT 2
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin
# don't share IOMCU DMA

View File

@ -139,8 +139,6 @@ define HAL_I2C_INTERNAL_MASK 0
# no onboard SD, filesystem support disabled until flash logging implemented
#define HAL_OS_FATFS_IO 1
#define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
#define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# OSD support
define OSD_ENABLED 1

View File

@ -99,9 +99,6 @@ BARO MS56XX I2C:0:0x77
define HAL_WITH_RAMTRON 1
# enable FAT filesystem support
define HAL_OS_FATFS_IO 1
# now some defines for logging and terrain data files
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# this defines the default maximum clock on I2C devices.
define HAL_I2C_MAX_CLOCK 100000

View File

@ -100,9 +100,6 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_WITH_RAMTRON 1
# enable FAT filesystem support
define HAL_OS_FATFS_IO 1
# now some defines for logging and terrain data files
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# define the order that I2C buses
I2C_ORDER I2C1 I2C2

View File

@ -116,9 +116,6 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_WITH_RAMTRON 1
# enable FAT filesystem support
define HAL_OS_FATFS_IO 1
# now some defines for logging and terrain data files
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# define the order that I2C buses
I2C_ORDER I2C1 I2C2

View File

@ -123,9 +123,6 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_WITH_RAMTRON 1
# enable FAT filesystem support
define HAL_OS_FATFS_IO 1
# now some defines for logging and terrain data files
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# define the order that I2C buses
I2C_ORDER I2C1 I2C2

View File

@ -64,7 +64,6 @@ FLASH_RESERVE_START_KB 256
define GPS_UBLOX_MOVING_BASELINE TRUE
define HAL_GCS_ENABLED 1
define HAL_LOGGING_ENABLED TRUE
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_NO_MONITOR_THREAD
@ -198,8 +197,6 @@ PB2 BOOT1 INPUT
define CAN_APP_NODE_NAME "com.cubepilot.herepro"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# disabled compass cal as it doesn't work for now
# define COMPASS_CAL_ENABLED 1

View File

@ -313,9 +313,6 @@ DMA_PRIORITY SDMMC* UART8* ADC* SPI* TIM*
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# uncomment block below to enable a 2nd MS5611 baro on SPI5
#PF7 SPI5_SCK SPI5
#PF8 SPI5_MISO SPI5

View File

@ -137,8 +137,6 @@ BARO BMP280 I2C:0:0x76
define HAL_BARO_ALLOW_INIT_NO_BARO
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define STM32_PWM_USE_ADVANCED TRUE

View File

@ -206,8 +206,6 @@ IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_270
BARO BMP280 I2C:0:0x76
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# setup for OSD
define OSD_ENABLED 1

View File

@ -150,8 +150,6 @@ IMU Invensense SPI:mpu6000 ROTATION_YAW_180
BARO BMP280 I2C:0:0x76
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# setup for OSD
undef OSD_ENABLED # minimize_features.inc removes this

View File

@ -6,8 +6,6 @@ undef sdcard
undef mpu6000
undef IMU
undef HAL_OS_FATFS_IO
undef HAL_BOARD_LOG_DIRECTORY
undef HAL_BOARD_TERRAIN_DIRECTORY
undef PA3 PA0 PA2 PC8 PC9 PD8 PD9 PD0 PD1 PC6 PC7 PE7 PE8
MCU_CLOCKRATE_MHZ 480

View File

@ -135,9 +135,6 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES
SPIDEV sdcard SPI3 DEVID3 SDCARD_CS MODE0 400*KHZ 25*MHZ
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# --------------------- DPS310 ------------------------
BARO DPS280 I2C:0:0x76

View File

@ -138,9 +138,6 @@ SPIDEV dataflash SPI2 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ
define HAL_LOGGING_DATAFLASH_ENABLED 1
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# ----------------- I2C compass & Baro -----------------
# no built-in compass, but probe the i2c bus for all possible

View File

@ -157,8 +157,6 @@ define AP_BARO_BMP280_ENABLED 1
define AP_BARO_DPS280_ENABLED 1
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# define default battery setup
define HAL_BATT_MONITOR_DEFAULT 4

View File

@ -150,8 +150,6 @@ SPIDEV osd SPI2 DEVID1 MAX7456_CS MODE0 10*MHZ 10*MHZ
# filesystem setup on sdcard
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# setup for OSD
define OSD_ENABLED 1

View File

@ -206,8 +206,6 @@ BARO DPS310 I2C:0:0x76
BARO MS56XX I2C:0:0x77
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# setup for OSD
define OSD_ENABLED 1

View File

@ -216,8 +216,6 @@ BARO DPS310 I2C:0:0x76
BARO BMP280 I2C:0:0x76
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# setup for OSD
define OSD_ENABLED 1

View File

@ -158,8 +158,6 @@ IMU Invensense SPI:icm20689 ROTATION_YAW_180
BARO BMP280 I2C:0:0x76
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define STM32_PWM_USE_ADVANCED TRUE

View File

@ -116,9 +116,6 @@ PB11 I2C2_SDA I2C2
# Enable FAT filesystem support (needs a microSD defined via SDMMC).
define HAL_OS_FATFS_IO 1
# Now some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# barometers
BARO BMP388 I2C:0:0x77

View File

@ -115,8 +115,6 @@ SPIDEV sdcard SPI4 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
SPIDEV osd SPI2 DEVID1 MAX7456_CS MODE0 10*MHZ 10*MHZ
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# no built-in compass, but probe the i2c bus for all possible
# external compass types

View File

@ -302,9 +302,6 @@ DMA_PRIORITY SDMMC* UART8* ADC* SPI1* TIM*
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin

View File

@ -140,11 +140,6 @@ SPIDEV lsm9ds0_g SPI2 DEVID4 GYRO_CS MODE3 11*MHZ 11*MHZ
# enable FAT filesystem
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# pixracer has 3 LEDs, Red, Green, Blue
define HAL_HAVE_PIXRACER_LED

View File

@ -197,10 +197,6 @@ COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180_YAW_270
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 16384
define HAL_WITH_RAMTRON 1

View File

@ -213,8 +213,6 @@ undef AP_FEATURE_SBUS_OUT
# Enable FAT filesystem support.
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 1

View File

@ -180,10 +180,6 @@ COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180_YAW_270
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 16384
define HAL_WITH_RAMTRON 1

View File

@ -316,7 +316,4 @@ DMA_PRIORITY SDMMC* USART6* ADC* UART* USART* SPI* TIM*
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin

View File

@ -257,7 +257,4 @@ DMA_PRIORITY SDMMC* USART6* ADC* UART* USART* SPI* TIM*
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin

View File

@ -354,9 +354,6 @@ DMA_PRIORITY SDMMC* USART6* ADC* UART* USART* SPI* TIM*
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin
# enable DFU reboot for installing bootloader

View File

@ -174,9 +174,6 @@ SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
define HAL_CHIBIOS_ARCH_FMUV4 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 16384
# enable RAMTROM parameter storage

View File

@ -126,8 +126,6 @@ define HAL_WITH_RAMTRON 1
# enable FAT filesystem support
define HAL_OS_FATFS_IO 1
# now some defines for logging and terrain data files
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# define the order that I2C buses
I2C_ORDER I2C2 I2C1

View File

@ -223,8 +223,6 @@ PE6 EXTERN_GPIO4 OUTPUT GPIO(4)
# enable FAT filesystem support
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# enable RAMTROM parameter storage
define HAL_STORAGE_SIZE 32768

View File

@ -176,5 +176,3 @@ BARO SPL06 SPI:spl06
# FAT filesystem on microSD
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"

View File

@ -163,8 +163,6 @@ BARO DPS310 I2C:0:0x76
# filesystem setup on sdcard
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define STM32_PWM_USE_ADVANCED TRUE

View File

@ -186,8 +186,6 @@ define HAL_OSD_TYPE_DEFAULT 1
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define BOARD_PWM_COUNT_DEFAULT 11
define STM32_PWM_USE_ADVANCED TRUE

View File

@ -172,8 +172,6 @@ BARO BMP388 I2C:1:0x76
#ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define BOARD_PWM_COUNT_DEFAULT 9

View File

@ -134,8 +134,6 @@ define GPS_MOVING_BASELINE 1
# Logging
define HAL_LOGGING_ENABLED 1
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# SD Card pins
PC8 SDIO_D0 SDIO

View File

@ -158,8 +158,6 @@ SPIDEV sdcard SPI3 DEVID3 SDCARD_CS MODE0 400*KHZ 25*MHZ
# filesystem setup on sdcard
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# setup for OSD
define OSD_ENABLED 1

View File

@ -128,9 +128,6 @@ SPIDEV sdcard SPI3 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
define HAL_CHIBIOS_ARCH_BRAINV51 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 16384
# enable RAMTROM parameter storage

View File

@ -128,9 +128,6 @@ SPIDEV sdcard SPI3 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
define HAL_CHIBIOS_ARCH_BRAINV52 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 16384
# enable RAMTROM parameter storage

View File

@ -129,9 +129,6 @@ SPIDEV sdcard SPI3 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
define HAL_CHIBIOS_ARCH_BRAINV54 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 16384
# enable RAMTROM parameter storage

View File

@ -128,9 +128,6 @@ SPIDEV sdcard SPI3 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
define HAL_CHIBIOS_ARCH_COREV10 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 16384
# enable RAMTROM parameter storage

View File

@ -128,9 +128,6 @@ SPIDEV sdcard SPI3 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
define HAL_CHIBIOS_ARCH_UBRAINV51 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 15360
STORAGE_FLASH_PAGE 2
# reserve 32k for bootloader and 32k for flash storage

View File

@ -217,10 +217,6 @@ PD2 SDMMC1_CMD SDMMC1
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# enable RAMTROM parameter storage
define HAL_STORAGE_SIZE 32768
define HAL_WITH_RAMTRON 1

View File

@ -425,10 +425,6 @@ SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
# a #define in the hwdef.h header.
define HAL_CHIBIOS_ARCH_FMUV3 1
# Nnow some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# We need to tell HAL_ChibiOS/Storage.cpp how much storage is
# available (in bytes).
define HAL_STORAGE_SIZE 16384

View File

@ -425,10 +425,6 @@ SPIDEV pixartPC15 SPI4 DEVID13 ACCEL_EXT_CS MODE3 2*MHZ 2*MHZ
# a #define in the hwdef.h header.
define HAL_CHIBIOS_ARCH_FMUV3 1
# Nnow some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# We need to tell HAL_ChibiOS/Storage.cpp how much storage is
# available (in bytes).
define HAL_STORAGE_SIZE 16384

View File

@ -303,9 +303,6 @@ DMA_PRIORITY SDMMC* UART8* ADC* SPI* TIM*
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin
# uncomment block below to enable a 2nd MS5611 baro on SPI5

View File

@ -133,9 +133,6 @@ SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
SPIDEV dwm1000 SPI4 DEVID5 UWB_CS MODE0 3*MHZ 20*MHZ
define HAL_CHIBIOS_ARCH_FMUV4 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 16384
# enable RAMTROM parameter storage

View File

@ -190,10 +190,6 @@ SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
SPIDEV icm42605 SPI4 DEVID4 IMU_CS MODE3 2*MHZ 16*MHZ
SPIDEV icm42688 SPI4 DEVID4 IMU_CS MODE3 2*MHZ 16*MHZ
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 16384
# enable RAMTROM parameter storage

View File

@ -258,10 +258,6 @@ SPIDEV icm20948 SPI1 DEVID1 ICM_20948_CS MODE3 2*MHZ 4*MHZ
SPIDEV dps310 SPI2 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ
SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
# Now some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 1

View File

@ -220,10 +220,6 @@ SPIDEV bmi088_a SPI5 DEVID2 BMI088_ACCEL_CS MODE3 5*MHZ 5*MHZ
SPIDEV icm20608 SPI1 DEVID2 ICM_20602_CS MODE3 2*MHZ 4*MHZ
SPIDEV icm20948 SPI1 DEVID1 ICM_20948_CS MODE3 2*MHZ 4*MHZ
# Now some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 1

View File

@ -223,10 +223,6 @@ SPIDEV bmi088_a SPI5 DEVID2 BMI088_ACCEL_CS MODE3 5*MHZ 5*MHZ
SPIDEV icm20608 SPI1 DEVID2 ICM_20602_CS MODE3 2*MHZ 4*MHZ
SPIDEV icm20948 SPI1 DEVID1 ICM_20948_CS MODE3 2*MHZ 4*MHZ
# Now some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# Enable RAMTROM parameter storage.
define HAL_WITH_RAMTRON 1

View File

@ -235,10 +235,6 @@ SPIDEV bmi088_a SPI5 DEVID2 BMI088_ACCEL_CS MODE3 5*MHZ 5*MHZ
SPIDEV icm20608 SPI1 DEVID2 ICM_20602_CS MODE3 2*MHZ 4*MHZ
SPIDEV icm20948 SPI1 DEVID1 ICM_20948_CS MODE3 2*MHZ 4*MHZ
# Now some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# Enable RAMTROM parameter storage.
define HAL_WITH_RAMTRON 1

View File

@ -146,10 +146,6 @@ SPIDEV rm3100 SPI3 DEVID4 CS_RM3100 MODE3 2*MHZ 8*MHZ
SPIDEV dps310 SPI4 DEVID3 CS_DPS310 MODE3 5*MHZ 5*MHZ
SPIDEV ramtron SPI4 DEVID10 CS_FRAM MODE3 8*MHZ 8*MHZ
# Now some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 0

View File

@ -236,10 +236,6 @@ SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
SPIDEV bmi088_g SPI5 DEVID1 BMI088_GYRO_CS MODE3 10*MHZ 10*MHZ
SPIDEV bmi088_a SPI5 DEVID2 BMI088_ACCEL_CS MODE3 10*MHZ 10*MHZ
# Now some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# Enable FAT filesystem support (needs a microSD defined via SDMMC).
define HAL_OS_FATFS_IO 1

View File

@ -384,10 +384,6 @@ SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
# a #define in the hwdef.h header
define HAL_CHIBIOS_ARCH_FMUV3 1
# now some defines for logging and terrain data files
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# we need to tell HAL_ChibiOS/Storage.cpp how much storage is
# available (in bytes)
define HAL_STORAGE_SIZE 32768

View File

@ -183,9 +183,6 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_CHIBIOS_ARCH_MINDPXV2 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 16384
# enable RAMTROM parameter storage

View File

@ -127,9 +127,6 @@ COMPASS QMC5883L I2C:0:0x0D false ROTATION_PITCH_180_YAW_270
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 16384
# enable RAMTROM parameter storage

View File

@ -250,9 +250,6 @@ PD7 SDMMC2_CMD SDMMC2
define FATFS_HAL_DEVICE SDCD2
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# red LED
PB0 LED_RED OUTPUT OPENDRAIN GPIO(90)
PB1 LED_GREEN OUTPUT OPENDRAIN GPIO(91)

View File

@ -134,8 +134,6 @@ STORAGE_FLASH_PAGE 1
define HAL_STORAGE_SIZE 15360
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# define default battery setup
define HAL_BATT_VOLT_PIN 12

View File

@ -305,9 +305,6 @@ PE10 SAFETY_IN INPUT PULLDOWN
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
DMA_PRIORITY ADC* SPI1* TIM*UP*
DMA_NOSHARE SPI1* TIM*UP*

View File

@ -16,8 +16,6 @@ undef HAL_LOGGING_DATAFLASH_ENABLED
# filesystem setup on sdcard
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# disable SMBUS monitors to save flash
define AP_BATTERY_SMBUS_ENABLED 0

View File

@ -24,8 +24,6 @@ undef AP_FEATURE_RTSCTS
undef HAL_WITH_RAMTRON
undef IOMCU_UART
undef SDIO
undef HAL_BOARD_LOG_DIRECTORY
undef HAL_BOARD_TERRAIN_DIRECTORY
# short board name override (13 chars) to match original max length; can't change because name is used for transmitter bind CRC
define CHIBIOS_SHORT_BOARD_NAME "skyviper-v245"

View File

@ -145,8 +145,6 @@ SPIDEV sdcard SPI2 DEVID2 SDCARD_CS MODE0 400*KHZ 25*MHZ
# filesystem setup on sdcard
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# setup for OSD
define OSD_ENABLED 1

View File

@ -247,10 +247,6 @@ BARO MS56XX SPI:ms5611
define HAL_CHIBIOS_ARCH_FMUV3 1
define BOARD_TYPE_DEFAULT 3
# Nnow some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# We need to tell HAL_ChibiOS/Storage.cpp how much storage is
# available (in bytes).
define HAL_STORAGE_SIZE 16384
@ -289,4 +285,4 @@ ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin
# for users running fmuv3 on their Solo:
define HAL_OREO_LED_ENABLED (BOARD_FLASH_SIZE > 1024)
define HAL_SOLO_GIMBAL_ENABLED (HAL_MOUNT_ENABLED && BOARD_FLASH_SIZE > 1024)
define HAL_SOLO_GIMBAL_ENABLED (HAL_MOUNT_ENABLED && BOARD_FLASH_SIZE > 1024)

View File

@ -247,10 +247,6 @@ BARO MS56XX SPI:ms5611
define HAL_CHIBIOS_ARCH_FMUV3 1
define BOARD_TYPE_DEFAULT 3
# Nnow some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# We need to tell HAL_ChibiOS/Storage.cpp how much storage is
# available (in bytes).
define HAL_STORAGE_SIZE 16384
@ -289,4 +285,4 @@ ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin
# for users running fmuv3 on their Solo:
define HAL_OREO_LED_ENABLED (BOARD_FLASH_SIZE > 1024)
define HAL_SOLO_GIMBAL_ENABLED (HAL_MOUNT_ENABLED && BOARD_FLASH_SIZE > 1024)
define HAL_SOLO_GIMBAL_ENABLED (HAL_MOUNT_ENABLED && BOARD_FLASH_SIZE > 1024)