mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
HAL_ChibiOS: fixed F405 PE15 afnum
should be 15 and not 1
This commit is contained in:
parent
9cc740b129
commit
d9b9638b4a
@ -382,7 +382,7 @@ AltFunction_map = {
|
||||
"PE14:TIM1_CH4" : 1,
|
||||
"PE15:TIM1_BKIN" : 1,
|
||||
"PE15:FSMC_D12" : 12,
|
||||
"PE15:EVENTOUT" : 1,
|
||||
"PE15:EVENTOUT" : 15,
|
||||
"PE1:DCMI_D3" : 13,
|
||||
"PE1:EVENTOUT" : 15,
|
||||
"PE1:FSMC_NBL1" : 12,
|
||||
|
Loading…
Reference in New Issue
Block a user