mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: enable BRD_PWM_VOLT_SEL parameter for mRoPixracerPro
This commit is contained in:
parent
683df64d86
commit
99ac8e2fbe
|
@ -209,8 +209,8 @@ PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH
|
|||
# 1.8V Sensor Level Shifter Output Enable. We pull it high by default.
|
||||
PI3 VDD_1V8_SENSORS_EN OUTPUT HIGH
|
||||
|
||||
# Set Output Logic Level, Default is 3.3v
|
||||
PG6 nSERVO_OUTPUT_3v3 OUTPUT LOW GPIO(74)
|
||||
# Pin for PWM Voltage Selection, 0 means 3.3v, 1 means 5v
|
||||
PG6 PWM_VOLT_SEL OUTPUT LOW GPIO(74)
|
||||
|
||||
# Power flag pins: these tell the MCU the status of the various power
|
||||
# supplies that are available. The pin names need to exactly match the
|
||||
|
|
Loading…
Reference in New Issue