AP_HAL_ChibiOS: use defaults to turn off CRSF telem on IO firmware

This commit is contained in:
Peter Barker 2023-04-26 17:55:10 +10:00 committed by Peter Barker
parent 67f137736a
commit 1f3aecf41b

View File

@ -3313,6 +3313,9 @@ def add_iomcu_firmware_defaults(f):
// disable some protocols on iomcu:
#define AP_RCPROTOCOL_FASTSBUS_ENABLED 0
// no crossfire telemetry from iomcu!
#define HAL_CRSF_TELEM_ENABLED 0
// end IOMCU Firmware defaults
''')