mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
HAL_ChibiOS: change CUAVv5Nano default PWM count to 11
This commit is contained in:
parent
021816ecbc
commit
ae2d4e6edc
@ -36,6 +36,9 @@ PA5 TIM2_CH1 TIM2 PWM(9) GPIO(58)
|
||||
PB3 TIM2_CH2 TIM2 PWM(10) GPIO(59)
|
||||
PB11 TIM2_CH4 TIM2 PWM(11) GPIO(60)
|
||||
|
||||
undef BOARD_PWM_COUNT_DEFAULT
|
||||
define BOARD_PWM_COUNT_DEFAULT 11
|
||||
|
||||
# RCInput on the PPM pin, for all protocols
|
||||
undef PG9
|
||||
undef USART6_RX
|
||||
|
Loading…
Reference in New Issue
Block a user