mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 10:43:58 -04:00
global: create and use HAL_PROGRAM_SIZE_LIMIT_KB
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
This commit is contained in:
parent
41b5f796b5
commit
6338d10b5f
@ -80,7 +80,7 @@ extern AP_Periph_FW periph;
|
||||
// especially helpful with HAL_GCS_ENABLED where libraries use the mavlink
|
||||
// send_text() method where we support strings up to 256 chars by splitting them
|
||||
// up into multiple 50 char mavlink packets.
|
||||
#define HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF (BOARD_FLASH_SIZE >= 1024)
|
||||
#define HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF (HAL_PROGRAM_SIZE_LIMIT_KB >= 1024)
|
||||
#endif
|
||||
|
||||
static struct instance_t {
|
||||
|
@ -5,7 +5,7 @@
|
||||
#include <GCS_MAVLink/GCS_config.h>
|
||||
|
||||
#ifndef HAL_ADSB_ENABLED
|
||||
#define HAL_ADSB_ENABLED BOARD_FLASH_SIZE > 1024
|
||||
#define HAL_ADSB_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef HAL_ADSB_BACKEND_DEFAULT_ENABLED
|
||||
|
@ -38,9 +38,9 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_AHRS_POSITION_RESET_ENABLED
|
||||
#define AP_AHRS_POSITION_RESET_ENABLED (BOARD_FLASH_SIZE>1024 && AP_AHRS_ENABLED)
|
||||
#define AP_AHRS_POSITION_RESET_ENABLED (HAL_PROGRAM_SIZE_LIMIT_KB>1024 && AP_AHRS_ENABLED)
|
||||
#endif
|
||||
|
||||
#ifndef AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED
|
||||
#define AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED (BOARD_FLASH_SIZE>1024 && AP_AHRS_DCM_ENABLED)
|
||||
#define AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED (HAL_PROGRAM_SIZE_LIMIT_KB>1024 && AP_AHRS_DCM_ENABLED)
|
||||
#endif
|
||||
|
@ -3,7 +3,7 @@
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_AIS_ENABLED
|
||||
#if BOARD_FLASH_SIZE <= 1024
|
||||
#if HAL_PROGRAM_SIZE_LIMIT_KB <= 1024
|
||||
#define AP_AIS_ENABLED 0
|
||||
#else
|
||||
#define AP_AIS_ENABLED 2
|
||||
|
@ -28,7 +28,7 @@
|
||||
// This could be removed once the build system allows for APM_BUILD_TYPE in header files
|
||||
// Note that this is also defined in AP_Airspeed_Params.cpp
|
||||
#ifndef AP_AIRSPEED_DUMMY_METHODS_ENABLED
|
||||
#define AP_AIRSPEED_DUMMY_METHODS_ENABLED ((APM_BUILD_COPTER_OR_HELI && BOARD_FLASH_SIZE <= 1024) || \
|
||||
#define AP_AIRSPEED_DUMMY_METHODS_ENABLED ((APM_BUILD_COPTER_OR_HELI && HAL_PROGRAM_SIZE_LIMIT_KB <= 1024) || \
|
||||
APM_BUILD_TYPE(APM_BUILD_AntennaTracker) || APM_BUILD_TYPE(APM_BUILD_Blimp))
|
||||
#endif
|
||||
|
||||
|
@ -26,7 +26,7 @@
|
||||
// This could be removed once the build system allows for APM_BUILD_TYPE in header files
|
||||
// note that this is re-definition of the one in AP_Airspeed.cpp, can't be shared as vehicle dependences cant go in header files
|
||||
#ifndef AP_AIRSPEED_DUMMY_METHODS_ENABLED
|
||||
#define AP_AIRSPEED_DUMMY_METHODS_ENABLED ((APM_BUILD_COPTER_OR_HELI && BOARD_FLASH_SIZE <= 1024) || \
|
||||
#define AP_AIRSPEED_DUMMY_METHODS_ENABLED ((APM_BUILD_COPTER_OR_HELI && HAL_PROGRAM_SIZE_LIMIT_KB <= 1024) || \
|
||||
APM_BUILD_TYPE(APM_BUILD_AntennaTracker) || APM_BUILD_TYPE(APM_BUILD_Blimp))
|
||||
#endif
|
||||
|
||||
|
@ -69,7 +69,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_AIRSPEED_HYGROMETER_ENABLE
|
||||
#define AP_AIRSPEED_HYGROMETER_ENABLE (AP_AIRSPEED_ENABLED && BOARD_FLASH_SIZE > 1024)
|
||||
#define AP_AIRSPEED_HYGROMETER_ENABLE (AP_AIRSPEED_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB > 1024)
|
||||
#endif
|
||||
|
||||
#ifndef AP_AIRSPEED_EXTERNAL_ENABLED
|
||||
|
@ -26,7 +26,7 @@
|
||||
#define AP_BATT_MONITOR_RES_EST_TC_1 0.5f
|
||||
#define AP_BATT_MONITOR_RES_EST_TC_2 0.1f
|
||||
|
||||
#if BOARD_FLASH_SIZE > 1024
|
||||
#if HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#define AP_BATT_MONITOR_CELLS_MAX 14
|
||||
#else
|
||||
#define AP_BATT_MONITOR_CELLS_MAX 12
|
||||
|
@ -3,7 +3,7 @@
|
||||
#include "AP_BattMonitor_Backend.h"
|
||||
|
||||
#ifndef AP_BATTERY_AD7091R5_ENABLED
|
||||
#define AP_BATTERY_AD7091R5_ENABLED (BOARD_FLASH_SIZE > 1024)
|
||||
#define AP_BATTERY_AD7091R5_ENABLED (HAL_PROGRAM_SIZE_LIMIT_KB > 1024)
|
||||
#endif
|
||||
|
||||
#if AP_BATTERY_AD7091R5_ENABLED
|
||||
|
@ -47,15 +47,15 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_BATTERY_FUELFLOW_ENABLED
|
||||
#define AP_BATTERY_FUELFLOW_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (BOARD_FLASH_SIZE > 1024)
|
||||
#define AP_BATTERY_FUELFLOW_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (HAL_PROGRAM_SIZE_LIMIT_KB > 1024)
|
||||
#endif
|
||||
|
||||
#ifndef AP_BATTERY_FUELLEVEL_PWM_ENABLED
|
||||
#define AP_BATTERY_FUELLEVEL_PWM_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (BOARD_FLASH_SIZE > 1024)
|
||||
#define AP_BATTERY_FUELLEVEL_PWM_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (HAL_PROGRAM_SIZE_LIMIT_KB > 1024)
|
||||
#endif
|
||||
|
||||
#ifndef AP_BATTERY_FUELLEVEL_ANALOG_ENABLED
|
||||
#define AP_BATTERY_FUELLEVEL_ANALOG_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (BOARD_FLASH_SIZE > 1024)
|
||||
#define AP_BATTERY_FUELLEVEL_ANALOG_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (HAL_PROGRAM_SIZE_LIMIT_KB > 1024)
|
||||
#endif
|
||||
|
||||
#ifndef AP_BATTERY_GENERATOR_ENABLED
|
||||
@ -67,7 +67,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_BATTERY_INA2XX_ENABLED
|
||||
#define AP_BATTERY_INA2XX_ENABLED (AP_BATTERY_BACKEND_DEFAULT_ENABLED && (BOARD_FLASH_SIZE > 1024))
|
||||
#define AP_BATTERY_INA2XX_ENABLED (AP_BATTERY_BACKEND_DEFAULT_ENABLED && (HAL_PROGRAM_SIZE_LIMIT_KB > 1024))
|
||||
#endif
|
||||
|
||||
#ifndef AP_BATTERY_INA3221_ENABLED
|
||||
@ -88,7 +88,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_BATTERY_SUM_ENABLED
|
||||
#define AP_BATTERY_SUM_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (BOARD_FLASH_SIZE > 1024)
|
||||
#define AP_BATTERY_SUM_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (HAL_PROGRAM_SIZE_LIMIT_KB > 1024)
|
||||
#endif
|
||||
|
||||
#ifndef AP_BATTERY_TORQEEDO_ENABLED
|
||||
@ -96,7 +96,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_BATTERY_AD7091R5_ENABLED
|
||||
#define AP_BATTERY_AD7091R5_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (BOARD_FLASH_SIZE > 1024)
|
||||
#define AP_BATTERY_AD7091R5_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (HAL_PROGRAM_SIZE_LIMIT_KB > 1024)
|
||||
#endif
|
||||
|
||||
// SMBus-subclass backends:
|
||||
|
@ -33,5 +33,5 @@
|
||||
#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) && BOARD_FLASH_SIZE > 1024
|
||||
#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
|
||||
|
@ -18,7 +18,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_CAMERA_MAVLINKCAMV2_ENABLED
|
||||
#define AP_CAMERA_MAVLINKCAMV2_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED && BOARD_FLASH_SIZE > 1024
|
||||
#define AP_CAMERA_MAVLINKCAMV2_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef AP_CAMERA_MOUNT_ENABLED
|
||||
|
@ -125,7 +125,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_COMPASS_QMC5883P_ENABLED
|
||||
#define AP_COMPASS_QMC5883P_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED && (BOARD_FLASH_SIZE > 1024)
|
||||
#define AP_COMPASS_QMC5883P_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED && (HAL_PROGRAM_SIZE_LIMIT_KB > 1024)
|
||||
#endif
|
||||
|
||||
#ifndef AP_COMPASS_QMC5883L_ENABLED
|
||||
|
@ -44,7 +44,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_DRONECAN_SEND_GPS
|
||||
#define AP_DRONECAN_SEND_GPS (BOARD_FLASH_SIZE > 1024)
|
||||
#define AP_DRONECAN_SEND_GPS (HAL_PROGRAM_SIZE_LIMIT_KB > 1024)
|
||||
#endif
|
||||
|
||||
#define AP_DRONECAN_SW_VERS_MAJOR 1
|
||||
@ -55,15 +55,15 @@
|
||||
|
||||
|
||||
#ifndef AP_DRONECAN_HOBBYWING_ESC_SUPPORT
|
||||
#define AP_DRONECAN_HOBBYWING_ESC_SUPPORT (BOARD_FLASH_SIZE>1024)
|
||||
#define AP_DRONECAN_HOBBYWING_ESC_SUPPORT (HAL_PROGRAM_SIZE_LIMIT_KB>1024)
|
||||
#endif
|
||||
|
||||
#ifndef AP_DRONECAN_HIMARK_SERVO_SUPPORT
|
||||
#define AP_DRONECAN_HIMARK_SERVO_SUPPORT (BOARD_FLASH_SIZE>1024)
|
||||
#define AP_DRONECAN_HIMARK_SERVO_SUPPORT (HAL_PROGRAM_SIZE_LIMIT_KB>1024)
|
||||
#endif
|
||||
|
||||
#ifndef AP_DRONECAN_SERIAL_ENABLED
|
||||
#define AP_DRONECAN_SERIAL_ENABLED AP_SERIALMANAGER_REGISTER_ENABLED && (BOARD_FLASH_SIZE>1024)
|
||||
#define AP_DRONECAN_SERIAL_ENABLED AP_SERIALMANAGER_REGISTER_ENABLED && (HAL_PROGRAM_SIZE_LIMIT_KB>1024)
|
||||
#endif
|
||||
|
||||
#ifndef AP_DRONECAN_VOLZ_FEEDBACK_ENABLED
|
||||
|
@ -5,7 +5,7 @@
|
||||
#include <AP_Scripting/AP_Scripting_config.h>
|
||||
|
||||
#ifndef HAL_EFI_ENABLED
|
||||
#define HAL_EFI_ENABLED BOARD_FLASH_SIZE > 1024
|
||||
#define HAL_EFI_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef AP_EFI_BACKEND_DEFAULT_ENABLED
|
||||
|
@ -3,7 +3,7 @@
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_EXTERNAL_AHRS_ENABLED
|
||||
#define HAL_EXTERNAL_AHRS_ENABLED BOARD_FLASH_SIZE > 1024
|
||||
#define HAL_EXTERNAL_AHRS_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef AP_EXTERNAL_AHRS_BACKEND_DEFAULT_ENABLED
|
||||
|
@ -21,7 +21,7 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#ifndef AP_FETTEC_ONEWIRE_ENABLED
|
||||
#define AP_FETTEC_ONEWIRE_ENABLED BOARD_FLASH_SIZE > 1024
|
||||
#define AP_FETTEC_ONEWIRE_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
// Support both full-duplex at 500Kbit/s as well as half-duplex at 2Mbit/s (optional feature)
|
||||
|
@ -158,7 +158,7 @@ int AP_Filesystem_Sys::open(const char *fname, int flags, bool allow_absolute_pa
|
||||
#if AP_FILESYSTEM_SYS_FLASH_ENABLED
|
||||
if (strcmp(fname, "flash.bin") == 0) {
|
||||
void *ptr = (void*)0x08000000;
|
||||
const size_t size = BOARD_FLASH_SIZE*1024;
|
||||
const size_t size = HAL_PROGRAM_SIZE_LIMIT_KB*1024;
|
||||
r.str->set_buffer((char*)ptr, size, size);
|
||||
}
|
||||
#endif
|
||||
|
@ -61,7 +61,7 @@
|
||||
#define UBLOX_MAX_EXTENSIONS 8
|
||||
#define UBLOX_GNSS_SETTINGS 1
|
||||
#ifndef UBLOX_TIM_TM2_LOGGING
|
||||
#define UBLOX_TIM_TM2_LOGGING (BOARD_FLASH_SIZE>1024)
|
||||
#define UBLOX_TIM_TM2_LOGGING (HAL_PROGRAM_SIZE_LIMIT_KB>1024)
|
||||
#endif
|
||||
|
||||
#define UBLOX_MAX_GNSS_CONFIG_BLOCKS 7
|
||||
|
@ -98,7 +98,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_RTCM_DECODE_ENABLED
|
||||
#define AP_GPS_RTCM_DECODE_ENABLED BOARD_FLASH_SIZE > 1024
|
||||
#define AP_GPS_RTCM_DECODE_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef HAL_GPS_COM_PORT_DEFAULT
|
||||
|
@ -23,5 +23,5 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_GENERATOR_RICHENPOWER_ENABLED
|
||||
#define AP_GENERATOR_RICHENPOWER_ENABLED AP_GENERATOR_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024
|
||||
#define AP_GENERATOR_RICHENPOWER_ENABLED AP_GENERATOR_BACKEND_DEFAULT_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
@ -152,6 +152,14 @@
|
||||
#error "No CONFIG_HAL_BOARD_SUBTYPE set"
|
||||
#endif
|
||||
|
||||
// HAL_PROGRAM_SIZE_LIMIT_KB is the amount of space we have for
|
||||
// instructions. on ChibiOS this is the sum of onboard and external
|
||||
// flash. BOARD_FLASH_SIZE is reserved for use in the HAL backends
|
||||
// (usually only ChibiOS) and should not be used in general code.
|
||||
#ifndef HAL_PROGRAM_SIZE_LIMIT_KB
|
||||
#error HAL_PROGRAM_SIZE_LIMIT_KB must be defined
|
||||
#endif
|
||||
|
||||
#ifndef HAL_OS_SOCKETS
|
||||
#define HAL_OS_SOCKETS 0
|
||||
#endif
|
||||
@ -201,12 +209,8 @@
|
||||
#define AP_EXTENDED_DSHOT_TELEM_V2_ENABLED HAL_REQUIRES_BDSHOT_SUPPORT
|
||||
#endif
|
||||
|
||||
#ifndef BOARD_FLASH_SIZE
|
||||
#define BOARD_FLASH_SIZE 2048
|
||||
#endif
|
||||
|
||||
#ifndef HAL_GYROFFT_ENABLED
|
||||
#define HAL_GYROFFT_ENABLED (BOARD_FLASH_SIZE > 1024)
|
||||
#define HAL_GYROFFT_ENABLED (HAL_PROGRAM_SIZE_LIMIT_KB > 1024)
|
||||
#endif
|
||||
|
||||
// enable AP_GyroFFT library only if required:
|
||||
@ -391,7 +395,7 @@
|
||||
|
||||
|
||||
#ifndef HAL_ENABLE_SENDING_STATS
|
||||
#define HAL_ENABLE_SENDING_STATS BOARD_FLASH_SIZE >= 256
|
||||
#define HAL_ENABLE_SENDING_STATS HAL_PROGRAM_SIZE_LIMIT_KB >= 256
|
||||
#endif
|
||||
|
||||
#ifndef HAL_GPIO_LED_ON
|
||||
@ -405,7 +409,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef HAL_WITH_POSTYPE_DOUBLE
|
||||
#define HAL_WITH_POSTYPE_DOUBLE BOARD_FLASH_SIZE > 1024
|
||||
#define HAL_WITH_POSTYPE_DOUBLE HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef HAL_INS_RATE_LOOP
|
||||
|
@ -22,6 +22,14 @@
|
||||
#define HAL_MEM_CLASS HAL_MEM_CLASS_20
|
||||
#endif
|
||||
|
||||
// FIXME: BOARD_FLASH_SIZE is not adjusted for flash pages used for
|
||||
// storage, for the bootloader sector or for wasted pages (eg. defunct
|
||||
// OSD storage page). These all impact the amount of space we have
|
||||
// for storing program!
|
||||
#ifndef HAL_PROGRAM_SIZE_LIMIT_KB
|
||||
#define HAL_PROGRAM_SIZE_LIMIT_KB (BOARD_FLASH_SIZE+EXT_FLASH_SIZE_MB*1024)
|
||||
#endif
|
||||
|
||||
#ifndef HAL_NUM_CAN_IFACES
|
||||
#define HAL_NUM_CAN_IFACES 0
|
||||
#endif
|
||||
|
@ -11,6 +11,10 @@
|
||||
#define HAL_BARO_DEFAULT HAL_BARO_NONE
|
||||
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_NONE
|
||||
|
||||
#ifndef HAL_PROGRAM_SIZE_LIMIT_KB
|
||||
#define HAL_PROGRAM_SIZE_LIMIT_KB 2048
|
||||
#endif
|
||||
|
||||
#define HAL_HAVE_BOARD_VOLTAGE 1
|
||||
#define HAL_HAVE_SERVO_VOLTAGE 0
|
||||
#define HAL_HAVE_SAFETY_SWITCH 1
|
||||
|
@ -35,6 +35,10 @@
|
||||
#define O_CLOEXEC 0
|
||||
#define HAL_STORAGE_SIZE (16384)
|
||||
|
||||
#ifndef HAL_PROGRAM_SIZE_LIMIT_KB
|
||||
#define HAL_PROGRAM_SIZE_LIMIT_KB 2048
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
// allow for static semaphores
|
||||
#include <AP_HAL_ESP32/Semaphores.h>
|
||||
|
@ -9,9 +9,9 @@
|
||||
#define HAL_STORAGE_SIZE 16384
|
||||
#define HAL_STORAGE_SIZE_AVAILABLE HAL_STORAGE_SIZE
|
||||
|
||||
#ifndef BOARD_FLASH_SIZE
|
||||
#define BOARD_FLASH_SIZE 4096
|
||||
#endif
|
||||
#ifndef HAL_PROGRAM_SIZE_LIMIT_KB
|
||||
#define HAL_PROGRAM_SIZE_LIMIT_KB 4096
|
||||
#endif // HAL_PROGRAM_SIZE_LIMIT_KB
|
||||
|
||||
#ifndef HAL_OPTFLOW_PX4FLOW_I2C_ADDRESS
|
||||
#define HAL_OPTFLOW_PX4FLOW_I2C_ADDRESS 0x42
|
||||
|
@ -8,6 +8,10 @@
|
||||
#define HAL_STORAGE_SIZE 32768
|
||||
#define HAL_STORAGE_SIZE_AVAILABLE HAL_STORAGE_SIZE
|
||||
|
||||
#ifndef HAL_PROGRAM_SIZE_LIMIT_KB
|
||||
#define HAL_PROGRAM_SIZE_LIMIT_KB 2048
|
||||
#endif
|
||||
|
||||
// only include if compiling C++ code
|
||||
#ifdef __cplusplus
|
||||
#include <AP_HAL_QURT/Semaphores.h>
|
||||
|
@ -29,8 +29,8 @@
|
||||
#define HAL_FLASH_ALLOW_UPDATE 0
|
||||
#endif
|
||||
|
||||
#ifndef BOARD_FLASH_SIZE
|
||||
#define BOARD_FLASH_SIZE 4096
|
||||
#ifndef HAL_PROGRAM_SIZE_LIMIT_KB
|
||||
#define HAL_PROGRAM_SIZE_LIMIT_KB 4096
|
||||
#endif
|
||||
|
||||
#ifndef HAL_STORAGE_SIZE
|
||||
|
@ -17,7 +17,7 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#ifndef HAL_HOTT_TELEM_ENABLED
|
||||
#define HAL_HOTT_TELEM_ENABLED BOARD_FLASH_SIZE > 2048
|
||||
#define HAL_HOTT_TELEM_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB > 2048
|
||||
#endif
|
||||
|
||||
#if HAL_HOTT_TELEM_ENABLED
|
||||
|
@ -36,7 +36,7 @@
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_IBUS_TELEM_ENABLED
|
||||
#define AP_IBUS_TELEM_ENABLED BOARD_FLASH_SIZE > 2048
|
||||
#define AP_IBUS_TELEM_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB > 2048
|
||||
#endif
|
||||
|
||||
#if AP_IBUS_TELEM_ENABLED
|
||||
|
@ -463,7 +463,7 @@ bool AP_InertialSensor_Invensense::update() /* front end */
|
||||
if (fast_reset_count) {
|
||||
// check if we have reported in the last 1 seconds or
|
||||
// fast_reset_count changed
|
||||
#if HAL_GCS_ENABLED && BOARD_FLASH_SIZE > 1024
|
||||
#if HAL_GCS_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
const uint32_t now = AP_HAL::millis();
|
||||
if (now - last_fast_reset_count_report_ms > 5000U) {
|
||||
last_fast_reset_count_report_ms = now;
|
||||
|
@ -44,7 +44,7 @@
|
||||
#define DEFAULT_IMU_LOG_BAT_MASK 0
|
||||
|
||||
#ifndef HAL_INS_TEMPERATURE_CAL_ENABLE
|
||||
#define HAL_INS_TEMPERATURE_CAL_ENABLE BOARD_FLASH_SIZE > 1024
|
||||
#define HAL_INS_TEMPERATURE_CAL_ENABLE HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
||||
|
@ -4,6 +4,6 @@
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_KDECAN_ENABLED
|
||||
#define AP_KDECAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && BOARD_FLASH_SIZE > 1024)
|
||||
#define AP_KDECAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_PROGRAM_SIZE_LIMIT_KB > 1024)
|
||||
#endif
|
||||
|
||||
|
@ -17,7 +17,7 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#ifndef AP_LTM_TELEM_ENABLED
|
||||
#define AP_LTM_TELEM_ENABLED BOARD_FLASH_SIZE > 2048
|
||||
#define AP_LTM_TELEM_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB > 2048
|
||||
#endif
|
||||
|
||||
#if AP_LTM_TELEM_ENABLED
|
||||
|
@ -3,5 +3,5 @@
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
|
||||
#ifndef HAL_LANDING_DEEPSTALL_ENABLED
|
||||
#define HAL_LANDING_DEEPSTALL_ENABLED (BOARD_FLASH_SIZE > 1024)
|
||||
#define HAL_LANDING_DEEPSTALL_ENABLED (HAL_PROGRAM_SIZE_LIMIT_KB > 1024)
|
||||
#endif
|
||||
|
@ -18,7 +18,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef HAL_MOUNT_GREMSY_ENABLED
|
||||
#define HAL_MOUNT_GREMSY_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED && BOARD_FLASH_SIZE > 1024
|
||||
#define HAL_MOUNT_GREMSY_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef HAL_MOUNT_SCRIPTING_ENABLED
|
||||
@ -47,19 +47,19 @@
|
||||
#endif
|
||||
|
||||
#ifndef HAL_MOUNT_XACTI_ENABLED
|
||||
#define HAL_MOUNT_XACTI_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS && BOARD_FLASH_SIZE > 1024
|
||||
#define HAL_MOUNT_XACTI_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS && HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef HAL_MOUNT_VIEWPRO_ENABLED
|
||||
#define HAL_MOUNT_VIEWPRO_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024
|
||||
#define HAL_MOUNT_VIEWPRO_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef HAL_MOUNT_CADDX_ENABLED
|
||||
#define HAL_MOUNT_CADDX_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024
|
||||
#define HAL_MOUNT_CADDX_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef AP_MOUNT_POI_TO_LATLONALT_ENABLED
|
||||
#define AP_MOUNT_POI_TO_LATLONALT_ENABLED HAL_MOUNT_ENABLED && AP_TERRAIN_AVAILABLE && BOARD_FLASH_SIZE > 1024
|
||||
#define AP_MOUNT_POI_TO_LATLONALT_ENABLED HAL_MOUNT_ENABLED && AP_TERRAIN_AVAILABLE && HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef HAL_MOUNT_TOPOTEK_ENABLED
|
||||
|
@ -5,5 +5,5 @@
|
||||
|
||||
// Needs SerialManager + (AHRS or GPS)
|
||||
#ifndef HAL_NMEA_OUTPUT_ENABLED
|
||||
#define HAL_NMEA_OUTPUT_ENABLED BOARD_FLASH_SIZE>1024 && HAL_GCS_ENABLED
|
||||
#define HAL_NMEA_OUTPUT_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB>1024 && HAL_GCS_ENABLED
|
||||
#endif
|
||||
|
@ -15,17 +15,17 @@
|
||||
|
||||
// body odomotry (which includes wheel encoding) on rover or 2M boards
|
||||
#ifndef EK3_FEATURE_BODY_ODOM
|
||||
#define EK3_FEATURE_BODY_ODOM EK3_FEATURE_ALL || APM_BUILD_TYPE(APM_BUILD_Rover) || BOARD_FLASH_SIZE > 1024
|
||||
#define EK3_FEATURE_BODY_ODOM EK3_FEATURE_ALL || APM_BUILD_TYPE(APM_BUILD_Rover) || HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
// external navigation on 2M boards
|
||||
#ifndef EK3_FEATURE_EXTERNAL_NAV
|
||||
#define EK3_FEATURE_EXTERNAL_NAV EK3_FEATURE_ALL || BOARD_FLASH_SIZE > 1024
|
||||
#define EK3_FEATURE_EXTERNAL_NAV EK3_FEATURE_ALL || HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
// drag fusion on 2M boards
|
||||
#ifndef EK3_FEATURE_DRAG_FUSION
|
||||
#define EK3_FEATURE_DRAG_FUSION EK3_FEATURE_ALL || BOARD_FLASH_SIZE > 1024
|
||||
#define EK3_FEATURE_DRAG_FUSION EK3_FEATURE_ALL || HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
// Beacon Fusion if beacon data available
|
||||
|
@ -20,7 +20,7 @@
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_PLUSCODE_ENABLE
|
||||
#define HAL_PLUSCODE_ENABLE BOARD_FLASH_SIZE > 1024
|
||||
#define HAL_PLUSCODE_ENABLE HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
|
||||
|
@ -51,7 +51,7 @@
|
||||
*/
|
||||
#ifndef AP_PARAM_MAX_EMBEDDED_PARAM
|
||||
#if FORCE_APJ_DEFAULT_PARAMETERS
|
||||
#if BOARD_FLASH_SIZE <= 1024
|
||||
#if HAL_PROGRAM_SIZE_LIMIT_KB <= 1024
|
||||
#define AP_PARAM_MAX_EMBEDDED_PARAM 1024
|
||||
#else
|
||||
#define AP_PARAM_MAX_EMBEDDED_PARAM 8192
|
||||
|
@ -5,7 +5,7 @@
|
||||
#include <AP_RangeFinder/AP_RangeFinder_config.h>
|
||||
|
||||
#ifndef HAL_PROXIMITY_ENABLED
|
||||
#define HAL_PROXIMITY_ENABLED BOARD_FLASH_SIZE > 1024
|
||||
#define HAL_PROXIMITY_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef AP_PROXIMITY_BACKEND_DEFAULT_ENABLED
|
||||
|
@ -85,7 +85,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
||||
#define AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024 && HAL_GCS_ENABLED
|
||||
#define AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB > 1024 && HAL_GCS_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RCPROTOCOL_UDP_ENABLED
|
||||
|
@ -10,7 +10,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED
|
||||
#define HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED OSD_ENABLED && OSD_PARAM_ENABLED && HAL_CRSF_TELEM_ENABLED && BOARD_FLASH_SIZE > 1024
|
||||
#define HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED OSD_ENABLED && OSD_PARAM_ENABLED && HAL_CRSF_TELEM_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef HAL_SPEKTRUM_TELEM_ENABLED
|
||||
|
@ -116,7 +116,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_NOOPLOOP_ENABLED
|
||||
#define AP_RANGEFINDER_NOOPLOOP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024
|
||||
#define AP_RANGEFINDER_NOOPLOOP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_NRA24_CAN_ENABLED
|
||||
@ -132,7 +132,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_RDS02UF_ENABLED
|
||||
#define AP_RANGEFINDER_RDS02UF_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024
|
||||
#define AP_RANGEFINDER_RDS02UF_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_SIM_ENABLED
|
||||
@ -152,7 +152,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_TOFSENSEF_I2C_ENABLED
|
||||
#define AP_RANGEFINDER_TOFSENSEF_I2C_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024
|
||||
#define AP_RANGEFINDER_TOFSENSEF_I2C_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_TRI2C_ENABLED
|
||||
@ -180,9 +180,9 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_JRE_SERIAL_ENABLED
|
||||
#define AP_RANGEFINDER_JRE_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024
|
||||
#define AP_RANGEFINDER_JRE_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_AINSTEIN_LR_D1_ENABLED
|
||||
#define AP_RANGEFINDER_AINSTEIN_LR_D1_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024
|
||||
#define AP_RANGEFINDER_AINSTEIN_LR_D1_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
@ -21,7 +21,7 @@
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_ROBOTISSERVO_ENABLED
|
||||
#define AP_ROBOTISSERVO_ENABLED BOARD_FLASH_SIZE > 1024
|
||||
#define AP_ROBOTISSERVO_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#if AP_ROBOTISSERVO_ENABLED
|
||||
|
@ -4,7 +4,7 @@
|
||||
#include <AP_SerialManager/AP_SerialManager_config.h>
|
||||
|
||||
#ifndef AP_SCRIPTING_ENABLED
|
||||
#define AP_SCRIPTING_ENABLED (BOARD_FLASH_SIZE > 1024)
|
||||
#define AP_SCRIPTING_ENABLED (HAL_PROGRAM_SIZE_LIMIT_KB > 1024)
|
||||
#endif
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
@ -16,5 +16,5 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||
#define AP_SCRIPTING_SERIALDEVICE_ENABLED AP_SERIALMANAGER_REGISTER_ENABLED && (BOARD_FLASH_SIZE>1024)
|
||||
#define AP_SCRIPTING_SERIALDEVICE_ENABLED AP_SERIALMANAGER_REGISTER_ENABLED && (HAL_PROGRAM_SIZE_LIMIT_KB>1024)
|
||||
#endif
|
||||
|
@ -57,7 +57,7 @@
|
||||
|
||||
|
||||
#ifndef AP_SERIALMANAGER_REGISTER_ENABLED
|
||||
#define AP_SERIALMANAGER_REGISTER_ENABLED BOARD_FLASH_SIZE > 1024 && (AP_NETWORKING_ENABLED || HAL_ENABLE_DRONECAN_DRIVERS)
|
||||
#define AP_SERIALMANAGER_REGISTER_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB > 1024 && (AP_NETWORKING_ENABLED || HAL_ENABLE_DRONECAN_DRIVERS)
|
||||
#endif
|
||||
|
||||
#ifndef AP_SERIALMANAGER_IMUOUT_ENABLED
|
||||
|
@ -7,9 +7,9 @@
|
||||
// Enabled 2 is enabled with dummy methods for all vehicles except Sub and SITL
|
||||
|
||||
#ifndef AP_TEMPERATURE_SENSOR_ENABLED
|
||||
#if BOARD_FLASH_SIZE <= 1024
|
||||
#if HAL_PROGRAM_SIZE_LIMIT_KB <= 1024
|
||||
#define AP_TEMPERATURE_SENSOR_ENABLED 0
|
||||
#elif BOARD_FLASH_SIZE > 2048
|
||||
#elif HAL_PROGRAM_SIZE_LIMIT_KB > 2048
|
||||
#define AP_TEMPERATURE_SENSOR_ENABLED 1
|
||||
#else
|
||||
#define AP_TEMPERATURE_SENSOR_ENABLED 2
|
||||
|
@ -3,5 +3,5 @@
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_TORQEEDO_ENABLED
|
||||
#define HAL_TORQEEDO_ENABLED BOARD_FLASH_SIZE > 1024
|
||||
#define HAL_TORQEEDO_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
@ -1051,7 +1051,7 @@ void AP_Vehicle::one_Hz_update(void)
|
||||
every 10s check if using a 2M firmware on a 1M board
|
||||
*/
|
||||
if (one_Hz_counter % 10U == 0) {
|
||||
#if defined(BOARD_CHECK_F427_USE_1M) && (BOARD_FLASH_SIZE>1024)
|
||||
#if defined(BOARD_CHECK_F427_USE_1M) && (HAL_PROGRAM_SIZE_LIMIT_KB>1024)
|
||||
if (!hal.util->get_soft_armed() && check_limit_flash_1M()) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, BOARD_CHECK_F427_USE_1M);
|
||||
}
|
||||
@ -1062,7 +1062,7 @@ void AP_Vehicle::one_Hz_update(void)
|
||||
every 30s check if using a 1M firmware on a 2M board
|
||||
*/
|
||||
if (one_Hz_counter % 30U == 0) {
|
||||
#if defined(BOARD_CHECK_F427_USE_1M) && (BOARD_FLASH_SIZE<=1024)
|
||||
#if defined(BOARD_CHECK_F427_USE_1M) && (HAL_PROGRAM_SIZE_LIMIT_KB<=1024)
|
||||
if (!hal.util->get_soft_armed() && !check_limit_flash_1M()) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, BOARD_CHECK_F427_USE_2M);
|
||||
}
|
||||
|
@ -8,7 +8,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_TRAMP_ENABLED
|
||||
#define AP_TRAMP_ENABLED AP_VIDEOTX_ENABLED && OSD_ENABLED && BOARD_FLASH_SIZE>1024
|
||||
#define AP_TRAMP_ENABLED AP_VIDEOTX_ENABLED && OSD_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB>1024
|
||||
#endif
|
||||
|
||||
#ifndef AP_SMARTAUDIO_ENABLED
|
||||
|
@ -4,7 +4,7 @@
|
||||
#include <GCS_MAVLink/GCS_config.h>
|
||||
|
||||
#ifndef HAL_VISUALODOM_ENABLED
|
||||
#define HAL_VISUALODOM_ENABLED BOARD_FLASH_SIZE > 1024
|
||||
#define HAL_VISUALODOM_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#ifndef AP_VISUALODOM_BACKEND_DEFAULT_ENABLED
|
||||
|
@ -36,7 +36,7 @@
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_VOLZ_ENABLED
|
||||
#define AP_VOLZ_ENABLED BOARD_FLASH_SIZE > 1024
|
||||
#define AP_VOLZ_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#if AP_VOLZ_ENABLED
|
||||
|
@ -3,15 +3,15 @@
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_FILTER_ENABLED
|
||||
#define AP_FILTER_ENABLED BOARD_FLASH_SIZE > 1024
|
||||
#define AP_FILTER_ENABLED HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#endif
|
||||
|
||||
#if AP_FILTER_ENABLED
|
||||
#ifndef AP_FILTER_NUM_FILTERS
|
||||
#if BOARD_FLASH_SIZE > 1024
|
||||
#if HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#define AP_FILTER_NUM_FILTERS 8
|
||||
#else
|
||||
#define AP_FILTER_NUM_FILTERS 4
|
||||
#endif // BOARD_FLASH_SIZE
|
||||
#endif // HAL_PROGRAM_SIZE_LIMIT_KB
|
||||
#endif // AP_FILTER_NUM_FILTERS
|
||||
#endif // AP_FILTER_ENABLED
|
||||
|
@ -15,7 +15,7 @@
|
||||
#define MAVLINK_START_UART_SEND(chan, size) comm_send_lock(chan, size)
|
||||
#define MAVLINK_END_UART_SEND(chan, size) comm_send_unlock(chan)
|
||||
|
||||
#if BOARD_FLASH_SIZE > 1024
|
||||
#if HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
// allow 8 telemetry ports, allowing for extra networking or CAN ports
|
||||
#define MAVLINK_COMM_NUM_BUFFERS 8
|
||||
#else
|
||||
|
@ -43,7 +43,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef HAL_MAVLINK_INTERVALS_FROM_FILES_ENABLED
|
||||
#define HAL_MAVLINK_INTERVALS_FROM_FILES_ENABLED ((AP_FILESYSTEM_FATFS_ENABLED || AP_FILESYSTEM_LITTLEFS_ENABLED || AP_FILESYSTEM_POSIX_ENABLED) && BOARD_FLASH_SIZE > 1024)
|
||||
#define HAL_MAVLINK_INTERVALS_FROM_FILES_ENABLED ((AP_FILESYSTEM_FATFS_ENABLED || AP_FILESYSTEM_LITTLEFS_ENABLED || AP_FILESYSTEM_POSIX_ENABLED) && HAL_PROGRAM_SIZE_LIMIT_KB > 1024)
|
||||
#endif
|
||||
|
||||
#ifndef AP_MAVLINK_MSG_RELAY_STATUS_ENABLED
|
||||
@ -100,11 +100,11 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_MAVLINK_MSG_HIGHRES_IMU_ENABLED
|
||||
#define AP_MAVLINK_MSG_HIGHRES_IMU_ENABLED (BOARD_FLASH_SIZE > 1024) && AP_INERTIALSENSOR_ENABLED
|
||||
#define AP_MAVLINK_MSG_HIGHRES_IMU_ENABLED (HAL_PROGRAM_SIZE_LIMIT_KB > 1024) && AP_INERTIALSENSOR_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED
|
||||
#define AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED (BOARD_FLASH_SIZE > 1024)
|
||||
#define AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED (HAL_PROGRAM_SIZE_LIMIT_KB > 1024)
|
||||
#endif
|
||||
|
||||
#ifndef AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED
|
||||
|
@ -7,7 +7,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef NUM_SERVO_CHANNELS
|
||||
#if BOARD_FLASH_SIZE > 1024
|
||||
#if HAL_PROGRAM_SIZE_LIMIT_KB > 1024
|
||||
#define NUM_SERVO_CHANNELS 32
|
||||
#else
|
||||
#define NUM_SERVO_CHANNELS 16
|
||||
|
Loading…
Reference in New Issue
Block a user