mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
HAL_ChibiOS: define INS_MAX_INSTANCES if less than 3
save some flash and memory
This commit is contained in:
parent
4ef7d5b468
commit
bb3b59966f
@ -1017,6 +1017,8 @@ def write_IMU_config(f):
|
|||||||
'#define HAL_INS_PROBE%u %s ADD_BACKEND(AP_InertialSensor_%s::probe(*this,%s))\n'
|
'#define HAL_INS_PROBE%u %s ADD_BACKEND(AP_InertialSensor_%s::probe(*this,%s))\n'
|
||||||
% (n, wrapper, driver, ','.join(dev[1:])))
|
% (n, wrapper, driver, ','.join(dev[1:])))
|
||||||
if len(devlist) > 0:
|
if len(devlist) > 0:
|
||||||
|
if len(devlist) < 3:
|
||||||
|
f.write('#define INS_MAX_INSTANCES %u\n' % len(devlist))
|
||||||
f.write('#define HAL_INS_PROBE_LIST %s\n\n' % ';'.join(devlist))
|
f.write('#define HAL_INS_PROBE_LIST %s\n\n' % ';'.join(devlist))
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user