mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
HAL_ChibiOS: define polarity of 3.3/5v selection for PWM
This commit is contained in:
parent
99ac8e2fbe
commit
d283dd7d00
@ -307,6 +307,7 @@ define HAL_BATT_CURR_PIN 15
|
||||
define HAL_BATT_VOLT_SCALE 10.1
|
||||
define HAL_BATT_CURR_SCALE 17.0
|
||||
define HAL_GPIO_PWM_VOLT_PIN 3
|
||||
define HAL_GPIO_PWM_VOLT_3v3 1
|
||||
|
||||
# List of files to put in ROMFS. For fmuv3 we need an IO firmware so
|
||||
# we can automatically update the IOMCU firmware on boot. The format
|
||||
|
@ -454,6 +454,7 @@ define HAL_BATT_CURR_PIN 3
|
||||
define HAL_BATT_VOLT_SCALE 10.1
|
||||
define HAL_BATT_CURR_SCALE 17.0
|
||||
define HAL_GPIO_PWM_VOLT_PIN 3
|
||||
define HAL_GPIO_PWM_VOLT_3v3 1
|
||||
|
||||
# this defines the default maximum clock on I2C devices.
|
||||
define HAL_I2C_MAX_CLOCK 100000
|
||||
|
@ -211,6 +211,8 @@ PI3 VDD_1V8_SENSORS_EN OUTPUT HIGH
|
||||
|
||||
# Pin for PWM Voltage Selection, 0 means 3.3v, 1 means 5v
|
||||
PG6 PWM_VOLT_SEL OUTPUT LOW GPIO(74)
|
||||
define HAL_GPIO_PWM_VOLT_PIN 74
|
||||
define HAL_GPIO_PWM_VOLT_3v3 0
|
||||
|
||||
# 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
Block a user