I’ve just merged support for the FrSky FPort RC protocol into master. I’d like to get some feedback from people willing to test it.
You can read more about FPort here:
The support has been tested on a X4R-SB receiver with the beta firmware loaded for FPort support. I have tested it on several boards and it is working for me, but I’d like a wider range of testers.
There are two aspects to FPort support. The first is support for the incoming RC protocol. That should work on all boards as we have a soft-serial implementation for receive of all RC protocols.
The 2nd aspect is SPort passthrough telemetry send, which is what allows you to use the Lua based telemetry display on a compatible transmitter, such as the yaapu telemetry scripts for a Taranis. That will only work when you setup RC input over a real UART, it won’t work if you are using the soft-serial RC input.
Configuration
The first thing you need is a receiver that supports the FPort protocol. Please see the betaflight page linked above for the list of supported receivers and also information on how to flash a receiver to support FPort. I used the method described here to flash my X4R with the right firmware.
After you have successfully bound your receiver to your transmitter with FPort and loaded the ArduPilot master firmware you should find that FPort RC input works by plugging your receiver into whatever RC input port you normally use on your flight controller. It should work for all boards.
You should also set RSSI_TYPE=3 in order to get RSSI input support. One of the nice things about FPort is that RSSI is part of the protocol, so we can properly log RSSI and also display it on the GCS.
Telemetry Support
Support for SPort telemetry is a bit more complex. I will explain the setup for a range of boards below. If you have a board that I don’t list below and you can’t work out how to configure it from these examples then please reply in the comments below and I’ll try to help you with the setup.
F7 and H7 Boards
All F7 and H7 based boards can support telemetry with FPort, but configuring some of them can be a bit tricky. First off you need to work out which serial port you will use. You then need to enable that serial port for RC input, and configure it for half-duplex and inverted operation. On some boards you may also need to set RC_OPTIONS=8 in order to enable an extra pad byte to work around an issue with pullups or level shifters on the port.
For example, here is the setup I have tested on a CubeOrange with RC input on telem2:
- SERIAL2_PROTCOL=23
- SERIAL2_OPTIONS=7
- RC_OPTIONS=8
- RSSI_TYPE=3
you will need to reboot after setting those options.
With the above setup you should connect the signal line of your FPort receiver to the TX line of the telem2 port. This means you will have a 3 wire cable going between the receiver and the telem2 port. The 3 pins are ground, 5v and signal.
Note that RC_OPTIONS is set to 8 is this example for CubeOrange. That is required for the CubeOrange and similar boards as they have a level shifter on all of their UARTs as a protection mechanism. This level shifter interferes with half-duplex operation. I have found that by adding a pad byte on the telemetry output the receiver is able to communicate correctly despite the level shifter. Unfortunately adding the pad byte on boards that don’t have this level shifter will break the FPort telemetry protocol, so we can’t just unconditionally add it, which is why we have the RC_OPTIONS bit available as a user configuration setting.
CUAVv5Nano
The CUAVv5Nano is a board which has a UART already tied into the normal RCIN port, which means it can support FPort telemetry without using any extra UART. The UART is mapped to SERIAL5 in ArduPilot. To enable FPort on a CUAVv5Nano setup as follows:
- SERIAL5_PROTOCOL=23
- SERIAL5_OPTIONS=7
- RSSI_TYPE=3
MatekF765-Wing
The MatekF765-Wing is a special case as it is the first board to use the new “alternate configuration” capability that was added as part of the FPort changes.
The normal setup for RC input on the MatekF765-Wing is to use the RX6 pin. This is convenient as a 3 pin receiver cable neatly goes over the GND, 5v and RX6 pins. To setup this board for FPort use the following:
- BRD_ALT_CONFIG=1
- SERIAL7_PROTOCOL=23
- SERIAL7_OPTIONS=15
- RC_OPTIONS=8
- RSSI_TYPE=3
What this is doing is:
- setting up the RX6 pin as a USART6_RX pin instead of the default timer capture. This is done using the new BRD_ALT_CONFIG=1 parameter which enables lines marked as ALT(1) in the hwdef.dat. The RX6 pin is normally setup as timer capture on this board to allow for PPM input as well as all other RC protocols. That doesn’t allow for FPort as we need a real UART for transmitting the telemetry. So we add a new hwdef.dat line that redefines this pin as USART6_RX and then select that line using the BRD_ALT_CONFIG option
- setup the serial options to enable inversion, and half-duplex and pin swapping. The swapping is needed as half-duplex normally needs the data to be on the TX pin, but on this board it is on the RX pin so we use the SWAP option in SERIAL7_OPTIONS to swap the pins.
- set RC_OPTIONS=8 as the arrangement of the UART6_RX pin leaves us with a pullup that needs a pad byte on FPort to fix it. I hope to avoid the need for this in a future update.
Note that this BRD_ALT_CONFIG option for the MatekF765-Wing is just the beginning of what we can do with alternative configs. I expect a lot of boards will gain alternative configs soon. It can be used to do things like remap pins between UARTs and I2C which will be useful on a lot of smaller boards where pins may need to be remapped for different setups.
F4 Based Boards
If you have an F4 based board then you will need a bi-directional inverter, as current generations of FPort receivers use an inverted serial protocol. Once you have an inverter on a UART then FPort should be able to be used following the same instructions as above.
KakuteF7 and KakuteF7Mini
Connect FPort receiver to normal RCIN port (USART6_RX) and setup as follows:
- SERIAL6_PROTOCOL=23
- BRD_ALT_CONFIG=1
- SERIAL6_OPTIONS=15
- RSSI_TYPE=3
MatekF405-Wing
Connect an external inverter to USART2. Setup as follows:
- BRD_ALT_CONFIG=1
- SERIAL5_PROTOCOL=23
- SERIAL5_OPTIONS=160
- RSSI_TYPE=3
OmnibusF4Pro
Connect an external inverter to TELEM1 (USART1). Setup as follows:
- SERIAL1_PROTOCOL=23
- SERIAL1_OPTIONS=160
- RSSI_TYPE=3
OmnibusF7V2
Connect FPort receiver to normal RCIN port (USART2_RX) and setup as follows:
- SERIAL4_PROTOCOL=23
- BRD_ALT_CONFIG=1
- SERIAL4_OPTIONS=15
- RSSI_TYPE=3
Feedback
I would appreciate feedback, both good and bad, on how well this works on a variety of boards.
In the future I’d like to do a full soft-serial TX implementation which would allow telemetry to work on a much wider range of boards.