From 673aa5ceb7dd44d135301cbe0069ad1553f15819 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 30 Dec 2022 16:04:22 +1100 Subject: [PATCH] HAL_ChibiOS: default to max 1 rangefinder in periph --- libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index e9010f5522..2d699de378 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -2964,6 +2964,10 @@ def add_apperiph_defaults(f): #ifndef AP_BATT_MONITOR_MAX_INSTANCES #define AP_BATT_MONITOR_MAX_INSTANCES 1 #endif + +#ifndef RANGEFINDER_MAX_INSTANCES +#define RANGEFINDER_MAX_INSTANCES 1 +#endif ''') def add_bootloader_defaults(f):