mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_HAL_ChibiOS: reduce default BRD_PWM_COUNT to 4 for fmv3
also default relay pins to use aux out 5 and 6
This commit is contained in:
parent
a7d9f4eef7
commit
af6c5ebda1
@ -343,6 +343,12 @@ PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53)
|
|||||||
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
|
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
|
||||||
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
|
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
|
||||||
|
|
||||||
|
define BOARD_PWM_COUNT_DEFAULT 4
|
||||||
|
|
||||||
|
# relays default to use GPIO pins 54 and 55
|
||||||
|
define RELAY1_PIN_DEFAULT 54
|
||||||
|
define RELAY2_PIN_DEFAULT 55
|
||||||
|
|
||||||
# this is the invensense data-ready pin. We don't use it in the
|
# this is the invensense data-ready pin. We don't use it in the
|
||||||
# default driver
|
# default driver
|
||||||
PD15 MPU_DRDY INPUT
|
PD15 MPU_DRDY INPUT
|
||||||
|
Loading…
Reference in New Issue
Block a user