mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
HAL_ChibiOS: fixed bug in undef of pins
revert pin to initial state on undef
This commit is contained in:
parent
8e6028ec1a
commit
20b2396646
@ -1974,11 +1974,8 @@ def process_line(line):
|
||||
alllines.remove(line)
|
||||
newpins = []
|
||||
for pin in allpins:
|
||||
if pin.type == a[1]:
|
||||
continue
|
||||
if pin.label == a[1]:
|
||||
continue
|
||||
if pin.portpin == a[1]:
|
||||
if pin.type == a[1] or pin.label == a[1] or pin.portpin == a[1]:
|
||||
portmap[pin.port][pin.pin] = generic_pin(pin.port, pin.pin, None, 'INPUT', [])
|
||||
continue
|
||||
newpins.append(pin)
|
||||
allpins = newpins
|
||||
|
Loading…
Reference in New Issue
Block a user