|
|
|
@ -28,7 +28,7 @@ STDOUT_BAUDRATE 57600
@@ -28,7 +28,7 @@ STDOUT_BAUDRATE 57600
|
|
|
|
|
I2C_ORDER I2C1 |
|
|
|
|
|
|
|
|
|
# order of UARTs (and USB) |
|
|
|
|
UART_ORDER OTG1 USART1 USART3 |
|
|
|
|
UART_ORDER OTG1 USART3 USART1 |
|
|
|
|
|
|
|
|
|
# rcinput is PC6, which is the 3rd "PWM IN" pin (the yellow wire on a |
|
|
|
|
# revolution board) |
|
|
|
@ -38,7 +38,14 @@ PC6 TIM8_CH1 TIM8 RCIN FLOAT LOW DMA_CH0
@@ -38,7 +38,14 @@ PC6 TIM8_CH1 TIM8 RCIN FLOAT LOW DMA_CH0
|
|
|
|
|
PC3 VDD_5V_SENS ADC1 |
|
|
|
|
PC2 BATT_VOLTAGE_SENS ADC1 SCALE(1) |
|
|
|
|
PC1 BATT_CURRENT_SENS ADC1 SCALE(1) |
|
|
|
|
PC5 USB_SENSE ADC1 |
|
|
|
|
PC5 USB_SENSE ADC1 |
|
|
|
|
|
|
|
|
|
# define default battery setup |
|
|
|
|
define HAL_BATT_VOLT_PIN 12 |
|
|
|
|
define HAL_BATT_CURR_PIN 11 |
|
|
|
|
define HAL_BATT_VOLT_SCALE 10.1 |
|
|
|
|
define HAL_BATT_CURR_SCALE 17.0 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
PC0 SBUS_INVERT OUTPUT LOW |
|
|
|
|
|
|
|
|
|