diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/README.md b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/README.md index db9a9d9393..b8760ff715 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/README.md @@ -28,24 +28,17 @@ receive pin for UARTn. The Tn pin is the transmit pin for UARTn. - SERIAL0 -> USB - SERIAL1 -> UART1 (ESC Telemetry) - SERIAL2 -> UART2 (RX, DMA-enabled) - - SERIAL3 -> UART3 (VTX) - - SERIAL4 -> UART4 + - SERIAL3 -> UART3 (VTX Tramp) + - SERIAL4 -> UART4 (MSP DisplayPort, DMA-enabled) - SERIAL5 -> UART5 (GPS, DMA-enabled) - - SERIAL6 -> UART6 + - SERIAL6 -> UART6 (RX in DJI connector) ## RC Input RC input is configured by default on the R2 (UART2_RX) pad. It supports all serial RC -protocols. For protocols requiring separate half-duplex serial to transmit -telemetry (such as FPort) you should setup SERIAL1 as an RC input serial port, -with half-duplex, pin-swap and inversion enabled. - -## FrSky Telemetry - -FrSky Telemetry can be supported using the T1 pin (UART1 transmit). You need to set the following parameters to enable support for FrSky S.PORT - - - SERIAL1_PROTOCOL 10 - - SERIAL1_OPTIONS 7 +protocols. Half-duplex serial protocols should be configured on T2 (UART2_TX). RC input is also +supported on UART6_RX within the DJI connector, although because it is not inverted it cannot be +used for SBUS. ## OSD Support @@ -66,7 +59,9 @@ The PWM is in 4 groups: Channels within the same group need to use the same output rate. If any channel in a group uses DShot then all channels in the group need -to use DShot. +to use DShot. Note that channel 9 is explicitly configured as NeoPixel output +which means that channel 5 cannot be used as a motor output without disabling NeoPixel +support on channel 9. ## Battery Monitoring @@ -86,6 +81,11 @@ The correct battery setting parameters are: The FoxeerF405v2 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. +## Control GPIO pins +GPIO pin 71 can be used to control camera switching. It is configured +by default on relay 3 and so you can associate an RC switch with relay 3 in order +to switch camera outputs. + ## Loading Firmware Initial firmware load can be done with DFU by plugging in USB with the diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/defaults.parm new file mode 100644 index 0000000000..9b8696da0c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/defaults.parm @@ -0,0 +1,5 @@ +# setup for LEDs on chan9 +SERVO9_FUNCTION 120 +NTF_LED_TYPES 257 + +GPS_DRV_OPTIONS 4 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat index a7ea2c9fa1..31b8c0a884 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat @@ -69,11 +69,12 @@ define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN # USART3 PC10 USART3_TX USART3 PC11 USART3_RX USART3 NODMA +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_Tramp # UART4 PA0 UART4_TX UART4 PA1 UART4_RX UART4 -define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_MSP_DisplayPort # UART5 PC12 UART5_TX UART5 NODMA