Skip to content

Commit

Permalink
HAL_ChibiOS: default RTS pins to PULLDOWN
Browse files Browse the repository at this point in the history
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:
ArduPilot#24169

this now applies it to all boards
  • Loading branch information
tridge committed Nov 11, 2023
1 parent 3811de3 commit 2f9bfb6
Showing 1 changed file with 7 additions and 2 deletions.
9 changes: 7 additions & 2 deletions libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py
Original file line number Diff line number Diff line change
Expand Up @@ -411,10 +411,15 @@ def get_PUPDR_value(self):
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"
Expand Down

0 comments on commit 2f9bfb6

Please sign in to comment.