mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed CTS pulldown
we need to pulldown to prevent delays in uart sends
This commit is contained in:
parent
a64819cbf2
commit
294aac6955
|
@ -221,7 +221,10 @@ class generic_pin(object):
|
|||
(self.label.endswith('_TX') or
|
||||
self.label.endswith('_RX'))):
|
||||
# default RX/TX lines to pullup, to prevent spurious bytes
|
||||
# on disconnected ports
|
||||
# on disconnected ports. CTS is the exception, which is pulldown
|
||||
if self.label.endswith("CTS"):
|
||||
v = "PULLDOWN"
|
||||
else:
|
||||
v = "PULLUP"
|
||||
for e in self.extra:
|
||||
if e in values:
|
||||
|
|
Loading…
Reference in New Issue