mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: default RTS pins to PULLDOWN
this avoids issues with SiK and RFD900x radios getting stuck in bootloader mode due to a high RTS pin on power on. We did this for Pixhawk6C in this PR: https://github.com/ArduPilot/ardupilot/pull/24169 this now applies it to all boards
This commit is contained in:
parent
3811de3e25
commit
2f9bfb648f
|
@ -411,10 +411,15 @@ class ChibiOSHWDef(object):
|
|||
self.type.startswith('UART')) and (
|
||||
(self.label.endswith('_TX') or
|
||||
self.label.endswith('_RX') or
|
||||
self.label.endswith('_CTS') or
|
||||
self.label.endswith('_RTS'))):
|
||||
self.label.endswith('_CTS'))):
|
||||
v = "PULLUP"
|
||||
|
||||
# pulldown on RTS to prevent radios from staying in bootloader
|
||||
if (self.type.startswith('USART') or
|
||||
self.type.startswith('UART')) and (
|
||||
self.label.endswith('_RTS')):
|
||||
v = "PULLDOWN"
|
||||
|
||||
if (self.type.startswith('SWD') and
|
||||
'SWDIO' in self.label):
|
||||
v = "PULLUP"
|
||||
|
|
Loading…
Reference in New Issue