AP_HAL_ChibiOS: adjust defaults to use param instead of hardcoded defaults

This commit is contained in:
Tom Pittenger 2020-12-22 15:30:41 -08:00 committed by Tom Pittenger
parent 4c484c8577
commit 083088bfff
1 changed files with 1 additions and 1 deletions

View File

@ -10,7 +10,7 @@ define AIRSPEED_MAX_SENSORS 1
define HAL_PERIPH_ENABLE_RANGEFINDER
define HAL_SERIAL3_PROTOCOL SerialProtocol_Rangefinder
define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 3
# we're too low on flash with old compiler for bootloader
define HAL_NO_ROMFS_SUPPORT