A receiver is used to receive radio control signals from your transmitter and convert them into signals that the flight controller can understand.
There are 3 basic types of receivers:
1. Parallel PWM Receivers
2. PPM Receivers
3. Serial Receivers
As of 2016 the recommendation for new purchases is a Serial or PPM based receiver. Avoid Parallel PWM recievers (1 wire per channel). This is due to the amount of IO pins parallel PWM based receivers use. Some new FC's do not support parallel PWM.
## Parallel PWM Receivers
8 channel support, 1 channel per input pin. On some platforms using parallel input will disable the use of serial ports
and SoftSerial making it hard to use telemetry or GPS features.
## PPM Receivers
PPM is sometimes known as PPM SUM or CPPM.
12 channels via a single input pin, not as accurate or jitter free as methods that use serial communications, but readily available.
* [FrSky D8R-XP 8ch telemetry receiver, or CPPM and RSSI enabled receiver](http://www.frsky-rc.com/product/pro.php?pro_id=21)
* [FrSky X4R and FrSky X4RSB](http://www.frsky-rc.com/download/view.php?sort=&down=158&file=X4R-X4RSB) when flashed with CPPM firmware and bound with jumper between signal pins 2 and 3
* All FrSky S.Bus enabled devices when connected with [S.Bus CPPM converter cable](http://www.frsky-rc.com/product/pro.php?pro_id=112). Without jumper this converter cable uses 21ms frame size (Channels 1-8). When jumper is in place, it uses 28ms frame and channels 1-12 are available
* FlySky/Turnigy FS-iA4B, FS-iA6B, FS-iA10 receivers all provide 8channels if the tx is sending them. (FS-i6 and FS-i10 transmitters). Use setting rx-setup/ppm to enable.
16 channels via serial currently supported. See below how to set up your transmitter.
* You probably need an inverter between the receiver output and the flight controller. However, some flight controllers have this built in (the main port on CC3D, for example), and doesn't need one.
* Some OpenLRS receivers produce a non-inverted SBUS signal. It is possible to switch SBUS inversion off using CLI command `set sbus_inversion = OFF` when using an F3 based flight controller.
* Softserial ports cannot be used with SBUS because it runs at too high of a bitrate (1Mbps). Refer to the chapter specific to your board to determine which port(s) may be used.
* You will need to configure the channel mapping in the GUI (Receiver tab) or CLI (`map` command). Note that channels above 8 are mapped "straight", with no remapping.
If using OpenTX set the transmitter module to D16 mode and ALSO select CH1-16 on the transmitter before binding to allow reception
of all 16 channels.
OpenTX 2.09, which is shipped on some Taranis X9D Plus transmitters, has a bug - [issue:1701](https://github.com/opentx/opentx/issues/1701).
The bug prevents use of all 16 channels. Upgrade to the latest OpenTX version to allow correct reception of all 16 channels,
without the fix you are limited to 8 channels regardless of the CH1-16/D16 settings.
### SRXL (formerly XBUS)
(Serial Receiver Link Protocol)
SRXL is an open data transfer protocol which allows to transport control data from a rc receiver to another device like a flybarless system
by only using one single line. This protocol has been established by SRXL.org based on the idea to create a freely available and unified protocol
that manufacturers can easily implement to their receivers and devices that process receiver data. The protocol does not describe an exact definition of
how the data must be processed. It only describes a framework in which receiver data can be packed. Each manufacturer can have his own ID, which must be
attached to the beginning of each data set, so that the device using this data can correctly identify and process the payload of the dataset.
Supported receivers:
#### Multiplex:
All receivers with SRXL (also FLEXX receivers)
####Gaupner / SJ HOTT:
All receiver with SUMD support
#### Spektrum:
AR7700 / AR9020 receiver
#### JR:
JR X-BUS
Make sure to set your TX to use "MODE B" for XBUS in the TX menus!
See here for info on JR's XBUS protocol: http://www.jrpropo.com/english/propo/XBus/
These receivers are reported working:
XG14 14ch DMSS System w/RG731BX XBus Receiver
http://www.jramericas.com/233794/JRP00631/
#### Jeti:
Receivers with UDI output
### XBUS MODE B RJ01
There exist a remote receiver made for small BNF-models like the Align T-Rex 150 helicopter. The code also supports using the Align DMSS RJ01 receiver directly with the cleanflight software.
To use this receiver you must power it with 3V from the hardware, and then connect the serial line as other serial RX receivers.
In order for this receiver to work, you need to specify the XBUS_MODE_B_RJ01 for serialrx_provider. Note that you need to set your radio mode for XBUS "MODE B" also for this receiver to work.
Allows you to use MSP commands as the RC input. Only 8 channel support to maintain compatibility with MSP.
## Configuration
There are 3 features that control receiver mode:
```
RX_PPM
RX_SERIAL
RX_PARALLEL_PWM
RX_MSP
```
Only one receiver feature can be enabled at a time.
### RX signal-loss detection
The software has signal loss detection which is always enabled. Signal loss detection is used for safety and failsafe reasons.
The `rx_min_usec` and `rx_max_usec` settings helps detect when your RX stops sending any data, enters failsafe mode or when the RX looses signal.
By default, when the signal loss is detected the FC will set pitch/roll/yaw to the value configured for `mid_rc`. The throttle will be set to the value configured for `rx_min_usec` or `mid_rc` if using 3D feature.
Signal loss can be detected when:
1. no rx data is received (due to radio reception, recevier configuration or cabling issues).
2. using Serial RX and receiver indicates failsafe condition.
3. using any of the first 4 stick channels do not have a value in the range specified by `rx_min_usec` and `rx_max_usec`.
### RX loss configuration
The `rxfail` cli command is used to configure per-channel rx-loss behaviour.
You can use the `rxfail` command to change this behaviour.
A flight channel can either be AUTOMATIC or HOLD, an AUX channel can either be SET or HOLD.
* AUTOMATIC - Flight channels are set to safe values (low throttle, mid position for yaw/pitch/roll).
* HOLD - Channel holds the last value.
* SET - Channel is set to a specific configured value.
The default mode is AUTOMATIC for flight channels and HOLD for AUX channels.
The rxfail command can be used in conjunction with mode ranges to trigger various actions.
The `rxfail` command takes 2 or 3 arguments.
* Index of channel (See below)
* Mode ('a' = AUTOMATIC, 'h' = HOLD, 's' = SET)
* A value to use when in SET mode.
Channels are always specified in the same order, regardless of your channel mapping.
* Roll is 0
* Pitch is 1
* Yaw is 2
* Throttle is 3.
* Aux channels are 4 onwards.
Examples:
To make Throttle channel have an automatic value when RX loss is detected:
`rxfail 3 a`
To make AUX4 have a value of 2000 when RX loss is detected:
`rxfail 7 s 2000`
To make AUX8 hold it's value when RX loss is detected:
`rxfail 11 h`
WARNING: Always make sure you test the behavior is as expected after configuring rxfail settings!
#### `rx_min_usec`
The lowest channel value considered valid. e.g. PWM/PPM pulse length
#### `rx_max_usec`
The highest channel value considered valid. e.g. PWM/PPM pulse length
### Serial RX
See the Serial chapter for some some RX configuration examples.
To setup spectrum on the Naze32 or clones in the GUI:
1. Start on the "Ports" tab make sure that UART2 has serial RX. If not set the checkbox, save and reboot.
2. Move to the "Configuration" page and in the upper lefthand corner choose Serial RX as the receiver type.
3. Below that choose the type of serial receiver that you are using. Save and reboot.
Using CLI:
For Serial RX enable `RX_SERIAL` and set the `serialrx_provider` CLI setting as follows.