mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-01 03:04:04 -04:00
We will reserve BOARD_FLASH_SIZE for the internal flash on stm32 flash processors, use HAL_PROGRAM_SIZE_LIMIT_KB in the general code base. Notable change here is that boards with external flash will start to get features only available with more than 2MB of program storage
38 lines
1.2 KiB
C
38 lines
1.2 KiB
C
#pragma once
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
#include <AP_Filesystem/AP_Filesystem_config.h>
|
|
|
|
#ifndef AP_FEATURE_BOARD_DETECT
|
|
#if defined(HAL_CHIBIOS_ARCH_FMUV3) || defined(HAL_CHIBIOS_ARCH_FMUV4) || defined(HAL_CHIBIOS_ARCH_FMUV5) || defined(HAL_CHIBIOS_ARCH_MINDPXV2) || defined(HAL_CHIBIOS_ARCH_FMUV4PRO) || defined(HAL_CHIBIOS_ARCH_BRAINV51) || defined(HAL_CHIBIOS_ARCH_BRAINV52) || defined(HAL_CHIBIOS_ARCH_UBRAINV51) || defined(HAL_CHIBIOS_ARCH_COREV10) || defined(HAL_CHIBIOS_ARCH_BRAINV54)
|
|
#define AP_FEATURE_BOARD_DETECT 1
|
|
#else
|
|
#define AP_FEATURE_BOARD_DETECT 0
|
|
#endif
|
|
#endif
|
|
|
|
#ifndef AP_FEATURE_RTSCTS
|
|
#define AP_FEATURE_RTSCTS 0
|
|
#endif
|
|
|
|
#ifndef AP_FEATURE_SBUS_OUT
|
|
#define AP_FEATURE_SBUS_OUT 0
|
|
#endif
|
|
|
|
#ifndef HAL_WATCHDOG_ENABLED_DEFAULT
|
|
#define HAL_WATCHDOG_ENABLED_DEFAULT false
|
|
#endif
|
|
|
|
#if HAL_HAVE_IMU_HEATER
|
|
#ifndef HAL_IMUHEAT_P_DEFAULT
|
|
#define HAL_IMUHEAT_P_DEFAULT 200
|
|
#endif
|
|
#ifndef HAL_IMUHEAT_I_DEFAULT
|
|
#define HAL_IMUHEAT_I_DEFAULT 0.3
|
|
#endif
|
|
#endif
|
|
|
|
#ifndef AP_SDCARD_STORAGE_ENABLED
|
|
#define AP_SDCARD_STORAGE_ENABLED (HAL_MEM_CLASS >= HAL_MEM_CLASS_1000) && (AP_FILESYSTEM_POSIX_ENABLED || AP_FILESYSTEM_FATFS_ENABLED) && HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
|
#endif
|