Skip to content

Commit

Permalink
global: create and use HAL_PROGRAM_SIZE_LIMIT_KB
Browse files Browse the repository at this point in the history
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
  • Loading branch information
peterbarker committed Feb 25, 2025
1 parent 41b5f79 commit 6338d10
Show file tree
Hide file tree
Showing 57 changed files with 112 additions and 88 deletions.
2 changes: 1 addition & 1 deletion Tools/AP_Periph/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_ADSB/AP_ADSB_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_AHRS/AP_AHRS_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
2 changes: 1 addition & 1 deletion libraries/AP_AIS/AP_AIS_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Airspeed/AP_Airspeed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Airspeed/AP_Airspeed_Params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Airspeed/AP_Airspeed_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_BattMonitor/AP_BattMonitor.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_BattMonitor/AP_BattMonitor_AD7091R5.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
12 changes: 6 additions & 6 deletions libraries/AP_BattMonitor/AP_BattMonitor_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand All @@ -88,15 +88,15 @@
#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
#define AP_BATTERY_TORQEEDO_ENABLED HAL_TORQEEDO_ENABLED
#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:
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_BoardConfig/AP_BoardConfig_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
2 changes: 1 addition & 1 deletion libraries/AP_Camera/AP_Camera_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Compass/AP_Compass_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
8 changes: 4 additions & 4 deletions libraries/AP_DroneCAN/AP_DroneCAN.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_EFI/AP_EFI_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_FETtecOneWire/AP_FETtecOneWire.h
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Filesystem/AP_Filesystem_Sys.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_GPS/AP_GPS_UBLOX.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_GPS/AP_GPS_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Generator/AP_Generator_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
18 changes: 11 additions & 7 deletions libraries/AP_HAL/AP_HAL_Boards.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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:
Expand Down Expand Up @@ -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
Expand All @@ -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
Expand Down
8 changes: 8 additions & 0 deletions libraries/AP_HAL/board/chibios.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_HAL/board/empty.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_HAL/board/esp32.h
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_HAL/board/linux.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_HAL/board/qurt.h
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_HAL/board/sitl.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Hott_Telem/AP_Hott_Telem.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_IBus_Telem/AP_IBus_Telem.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_InertialSensor/AP_InertialSensor_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Loading

0 comments on commit 6338d10

Please sign in to comment.