mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
HAL_ChibiOS: Reinstate HAL_MINIMIZE_FEATURES for 1MB F7 boards
This commit is contained in:
parent
6ed4eca57f
commit
ce361e51bf
@ -157,5 +157,9 @@ define HAL_BATTMON_FUEL_ENABLE 0
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
define HAL_SPRAYER_ENABLED 0
|
||||
|
||||
# save FLASH, but leave above when flash issue is fixed
|
||||
define HAL_MINIMIZE_FEATURES 1
|
||||
|
||||
|
||||
# reduce max size of embedded params for apj_tool.py
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
|
||||
|
@ -70,7 +70,7 @@ PA1 BMP280_CS CS
|
||||
|
||||
PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
|
||||
PC5 RSSI_ADC ADC1
|
||||
|
||||
# setup two IMUs
|
||||
@ -134,6 +134,9 @@ define HAL_BATTMON_FUEL_ENABLE 0
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
define HAL_SPRAYER_ENABLED 0
|
||||
|
||||
# save FLASH, but leave above when flash issue is fixed
|
||||
define HAL_MINIMIZE_FEATURES 1
|
||||
|
||||
# one baro
|
||||
BARO BMP280 SPI:bmp280
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user