mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_HAL_ChibOS: update hwdef,defaults.readme for KakuteH7
This commit is contained in:
parent
32488a5e3a
commit
176de8aa86
@ -25,13 +25,12 @@ receive pin for UARTn. The Tn pin is the transmit pin for UARTn.
|
|||||||
|
|
||||||
- SERIAL0 -> USB
|
- SERIAL0 -> USB
|
||||||
- SERIAL1 -> UART1 (Telem1)
|
- SERIAL1 -> UART1 (Telem1)
|
||||||
- SERIAL2 -> UART2 (Telem2)
|
- SERIAL2 -> UART2 (Telem2) (connected to internal BT module)
|
||||||
- SERIAL3 -> UART3 (GPS)
|
- SERIAL3 -> UART3 (GPS)
|
||||||
- SERIAL4 -> UART4
|
- SERIAL4 -> UART4
|
||||||
- SERIAL5 -> not available
|
- SERIAL5 -> not available
|
||||||
- SERIAL6 -> UART6
|
- SERIAL6 -> UART6
|
||||||
- SERIAL7 -> UART7
|
- SERIAL7 -> UART7
|
||||||
- SERIAL7 -> USB2
|
|
||||||
|
|
||||||
## RC Input
|
## RC Input
|
||||||
|
|
||||||
@ -43,7 +42,7 @@ and inversion enabled.
|
|||||||
|
|
||||||
## FrSky Telemetry
|
## FrSky Telemetry
|
||||||
|
|
||||||
FrSky Telemetry is supported using the T6 pin (UART6 transmit). You need to set the following parameters to enable support for FrSky S.PORT
|
FrSky Telemetry is supported using the Tx pin of any UART including SERIAL6/UART6 . You need to set the following parameters to enable support for FrSky S.PORT (example shows SERIAL6). Note this assumes the RC input is using default (ALT_BRD_CONFIG =0). Obviously, if using ALT_BRD_CONFIG = 1 for full duplex RC prtocols, you must a different UART for FrSky Telemetry.
|
||||||
|
|
||||||
- SERIAL6_PROTOCOL 10
|
- SERIAL6_PROTOCOL 10
|
||||||
- SERIAL6_OPTIONS 7
|
- SERIAL6_OPTIONS 7
|
||||||
|
@ -1,3 +1,5 @@
|
|||||||
# setup for LEDs on chan9
|
# setup for LEDs on chan9
|
||||||
SERVO9_FUNCTION 120
|
SERVO9_FUNCTION 120
|
||||||
NTF_LED_TYPES 257
|
NTF_LED_TYPES 257
|
||||||
|
SERIAL7_PROTOCOL 16
|
||||||
|
|
||||||
|
@ -28,7 +28,7 @@ define HAL_STORAGE_SIZE 32768
|
|||||||
I2C_ORDER I2C1
|
I2C_ORDER I2C1
|
||||||
|
|
||||||
# order of UARTs (and USB)
|
# order of UARTs (and USB)
|
||||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6 UART7 OTG2
|
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6 UART7
|
||||||
|
|
||||||
# buzzer
|
# buzzer
|
||||||
PC13 BUZZER OUTPUT LOW PULLDOWN GPIO(80)
|
PC13 BUZZER OUTPUT LOW PULLDOWN GPIO(80)
|
||||||
@ -72,7 +72,7 @@ PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
|
|||||||
|
|
||||||
PA8 VBUS INPUT
|
PA8 VBUS INPUT
|
||||||
|
|
||||||
# define default battery setup
|
# define default battery setup (note external current sensor required)
|
||||||
define HAL_BATT_VOLT_PIN 10
|
define HAL_BATT_VOLT_PIN 10
|
||||||
define HAL_BATT_CURR_PIN 11
|
define HAL_BATT_CURR_PIN 11
|
||||||
define HAL_BATT_VOLT_SCALE 11.0
|
define HAL_BATT_VOLT_SCALE 11.0
|
||||||
|
Loading…
Reference in New Issue
Block a user