mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: default off serial protocols in AP_Periph
this allows for a GPS on high numbered ports
This commit is contained in:
parent
14dca255a4
commit
23c0f257b6
|
@ -2161,6 +2161,11 @@ def add_apperiph_defaults(f):
|
||||||
#ifndef HAL_LOGGING_ENABLED
|
#ifndef HAL_LOGGING_ENABLED
|
||||||
#define HAL_LOGGING_ENABLED 0
|
#define HAL_LOGGING_ENABLED 0
|
||||||
#endif
|
#endif
|
||||||
|
// default to no protocols, AP_Periph enables with params
|
||||||
|
#define HAL_SERIAL1_PROTOCOL -1
|
||||||
|
#define HAL_SERIAL2_PROTOCOL -1
|
||||||
|
#define HAL_SERIAL3_PROTOCOL -1
|
||||||
|
#define HAL_SERIAL4_PROTOCOL -1
|
||||||
''')
|
''')
|
||||||
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue