mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
HAL_ChibiOS: default to max 1 rangefinder in periph
This commit is contained in:
parent
a89d5e1c83
commit
673aa5ceb7
@ -2964,6 +2964,10 @@ def add_apperiph_defaults(f):
|
|||||||
#ifndef AP_BATT_MONITOR_MAX_INSTANCES
|
#ifndef AP_BATT_MONITOR_MAX_INSTANCES
|
||||||
#define AP_BATT_MONITOR_MAX_INSTANCES 1
|
#define AP_BATT_MONITOR_MAX_INSTANCES 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef RANGEFINDER_MAX_INSTANCES
|
||||||
|
#define RANGEFINDER_MAX_INSTANCES 1
|
||||||
|
#endif
|
||||||
''')
|
''')
|
||||||
|
|
||||||
def add_bootloader_defaults(f):
|
def add_bootloader_defaults(f):
|
||||||
|
Loading…
Reference in New Issue
Block a user