HAL_ChibiOS: use pullup on CTS line
this makes life less difficult for SiK radios which go into bootloader mode on low CTS
This commit is contained in:
parent
11e09a846c
commit
409e857f6b
@ -247,11 +247,6 @@ class generic_pin(object):
|
||||
self.label.endswith('_RX') or
|
||||
self.label.endswith('_CTS') or
|
||||
self.label.endswith('_RTS'))):
|
||||
# default RX/TX lines to pullup, to prevent spurious bytes
|
||||
# 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
Block a user