landing tweaks
[inav.git] / docs / Rx.md
blobee600ce56c8ebaa5f2caeb50c3ad248ba1e850e6
1 # Receivers (RX)
3 A receiver is used to receive radio control signals from your transmitter and convert them into signals that the flight controller can understand.
5 There are 2 basic types of receivers:
7 1. PPM Receivers
8 2. Serial Receivers
10 ## PPM Receivers
12 **Only supported in INAV 3.x and below**
14 PPM is sometimes known as PPM SUM or CPPM.
16 12 channels via a single input pin, not as accurate or jitter free as methods that use serial communications, but readily available.
18 These receivers are reported working:
20 FrSky D4R-II
21 http://www.frsky-rc.com/product/pro.php?pro_id=24
23 Graupner GR24
24 http://www.graupner.de/en/products/33512/product.aspx
26 R615X Spektrum/JR DSM2/DSMX Compatible 6Ch 2.4GHz Receiver w/CPPM
27 http://orangerx.com/2014/05/20/r615x-spektrumjr-dsm2dsmx-compatible-6ch-2-4ghz-receiver-wcppm-2/
29 FrSky D8R-XP 8ch telemetry receiver, or CPPM and RSSI enabled receiver
30 http://www.frsky-rc.com/product/pro.php?pro_id=21
32 ## Serial Receivers
34 *Connect the receivers to UARTs and not to Software Serial ports. Using software serial for RX input can cause unexpected behaviours beacause the port cannot handle reliably the bit rate needed by the most common protocols*
36 ### Spektrum
38 This section describes the legacy Spektrum satellite capability; the newer SRXL2 protocol is described [later in this document](#srxl2) .
40 8 channels via serial currently supported.
42 These receivers are reported working:
44 Lemon Rx DSMX Compatible PPM 8-Channel Receiver + Lemon DSMX Compatible Satellite with Failsafe
45 http://www.lemon-rx.com/shop/index.php?route=product/product&product_id=118
48 #### Spektrum pesudo RSSI
50 As of INAV 1.6, a pseudo RSSI, based on satellite fade count is supported and reported as normal INAV RSSI (0-1023 range). In order to use this feature, the following is necessary:
52 * Bind the satellite receiver using a physical RX; the bind function provided by the flight controller is not sufficient.
53 * The CLI variable `rssi_channel` is set to channel 9:
54 ```
55 set rssi_channel = 9
56 ```
57 This pseudo-RSSI should work on all makes of Spektrum satellite RX; it is tested as working on [Lemon RX satellites](http://www.lemon-rx.com/index.php?route=product/product&path=72&product_id=109 and http://www.lemon-rx.com/index.php?route=product/product&path=72&product_id=135) (recommended).
59 ### S.BUS
61 16 channels via serial currently supported.  See below how to set up your transmitter.
63 * You probably need an inverter between the receiver output and the flight controller. However, some flight controllers have this built in and doesn't need one.
64 * 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.
65 * 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.
66 * 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.
68 These receivers are reported working:
70 FrSky X4RSB 3/16ch Telemetry Receiver
71 http://www.frsky-rc.com/product/pro.php?pro_id=135
73 FrSky X8R 8/16ch Telemetry Receiver
74 http://www.frsky-rc.com/product/pro.php?pro_id=105
76 Futaba R2008SB 2.4GHz S-FHSS
77 http://www.futaba-rc.com/systems/futk8100-8j/
80 #### OpenTX S.BUS configuration
82 If using OpenTX set the transmitter module to D16 mode and ALSO select CH1-16 on the transmitter before binding to allow reception
83 of all 16 channels.
85 OpenTX 2.09, which is shipped on some Taranis X9D Plus transmitters, has a bug - [issue:1701](https://github.com/opentx/opentx/issues/1701).
86 The bug prevents use of all 16 channels.  Upgrade to the latest OpenTX version to allow correct reception of all 16 channels,
87 without the fix you are limited to 8 channels regardless of the CH1-16/D16 settings.
90 ### F.Port
92 F.Port is a protocol running on async serial allowing 16 controls channels and telemetry on a single UART.
94 Supported receivers include FrSky R-XSR, X4R, X4R-SB, XSR, XSR-M, R9M Slim, R9M Slim+, R9 Mini. For ACCST receivers you need to flash the corresponding firmware for it to output F.Port. For ACCESS receivers the protocol output from the receiver can be switched between S.Bus and F.Port from the model's setup page in the RX options.
96 #### Connection
98 Just connect the S.Port wire from the receiver to the TX pad of a free UART on your flight controller
100 #### Configuration
102 For INAV 2.6 and newer versions, the default configuration should just work. However, if you're
103 upgrading from a previous version you might need to set the following settings to their
104 default values:
107 set serialrx_inverted = OFF
108 set serialrx_halfduplex = AUTO
111 For INAV versions prior to 2.6, you need to change the following settings:
114 set serialrx_inverted = ON
115 set serialrx_halfduplex = ON
118 ### SUMD
120 16 channels via serial currently supported.
122 These receivers are reported working:
124 GR-24 receiver HoTT
125 http://www.graupner.de/en/products/33512/product.aspx
127 Graupner receiver GR-12SH+ HoTT
128 http://www.graupner.de/en/products/870ade17-ace8-427f-943b-657040579906/33565/product.aspx
130 ### IBUS
132 10 channels via serial currently supported.
134 IBUS is the FlySky digital serial protocol and is available with the FS-IA6B, FS-X6B and FS-IA10 receivers.
135 The Turnigy TGY-IA6B and TGY-IA10 are the same devices with a different label, therefore they also work.
137 IBUS can provide up to 120Hz refresh rate, more than double compared to standard 50Hz of PPM.
139 FlySky FS-I6X TX natively supports 10ch.
141 If you are using a 6ch TX such as the FS-I6 or TGY-I6 then you must flash a 10ch
142 firmware on the TX to make use of these extra channels.
143 The flash is avaliable here: https://github.com/benb0jangles/FlySky-i6-Mod-
145      _______
146     /       \                               /------------\
147     | STM32 |-->UART RX-->[115200 baud]---->| Flysky RX  |
148     |  uC   |-  UART TX--x[not connected]   | IBUS-Servo |
149     \_______/                               \------------/
151 After flash "10ch Timer Mod i6 Updater", it is passible to get RSSI signal on selected Aux channel from FS-i6 Err sensor.
153 It is possible to use IBUS RX and IBUS telemetry on only one port of the hardware UART. More information in Telemetry.md.
155 ### SRXL2
157 SRXL2 is a newer Spektrum protocol that provides a bidirectional link between the FC and the receiver, allowing the user to get FC telemetry data and basic settings on Spektrum Gen 2 airware TX. SRXL2 is supported in INAV 2.6 and later. It offers improved performance and features compared to earlier Spektrum RX.
159 #### Wiring
161 Signal pin on receiver (labeled "S") must be wired to a **UART TX** pin on the FC. Voltage can be 3.3V (4.0V for SPM4651T) to 8.4V. On some F4 FCs, the TX pin may have a signal inverter (such as for S.Port). Make sure this isn't the case for the pin you intend to use.
163 #### Configuration
165 Selection of SXRL2 is provided in the INAV 2.6 and later configurators. It is necessary to complete the configuration via the CLI; the following settings are recommended:
168 feature TELEMETRY
169 feature -RSSI_ADC
170 map TAER
171 set receiver_type = SERIAL
172 set serialrx_provider = SRXL2
173 set serialrx_inverted = OFF
174 set srxl2_unit_id = 1
175 set srxl2_baud_fast = ON
176 set rssi_source = PROTOCOL
177 set rssi_channel = 0
180 #### Notes:
182 * RSSI_ADC is disabled, as this would override the value provided through SRXL2
183 * `rssi_channel = 0` is required, unlike earlier Spektrum devices (e.g. SPM4649T).
185 Setting these values differently may have an adverse effects on RSSI readings.
187 #### CLI Bind Command
189 This command will put the receiver into bind mode without the need to reboot the FC as it was required with the older `spektrum_sat_bind` command.
192 bind_rx
195 ## MultiWii serial protocol (MSP)
197 Allows you to use MSP commands as the RC input.  Only 8 channel support to maintain compatibility with MSP.
199 ## Configuration
201 The receiver type can be set from the configurator or CLI.
204 # get receiver_type
205 receiver_type = NONE
206 Allowed values: NONE, PPM, SERIAL, MSP, SPI, UIB
209 ### RX signal-loss detection
211 The software has signal loss detection which is always enabled.  Signal loss detection is used for safety and failsafe reasons.
213 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 loses signal.
215 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.
217 Signal loss can be detected when:
219 1. no rx data is received (due to radio reception, recevier configuration or cabling issues).
220 2. using Serial RX and receiver indicates failsafe condition.
221 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`.
223 #### `rx_min_usec`
225 The lowest channel value considered valid.  e.g. PWM/PPM pulse length
227 #### `rx_max_usec`
229 The highest channel value considered valid.  e.g. PWM/PPM pulse length
231 ### Serial RX
233 See the Serial chapter for some some RX configuration examples.
235 To setup spectrum in the GUI:
236 1. Start on the "Ports" tab make sure that UART2 has serial RX.  If not set the checkbox, save and reboot.
237 2. Move to the "Configuration" page and in the upper lefthand corner choose Serial RX as the receiver type.
238 3. Below that choose the type of serial receiver that you are using.  Save and reboot.
240 #### Using CLI:
242 For Serial RX set the `receiver_type` and `serialrx_provider` setting as appropriate for your RX.
245 # get rec
246 receiver_type = SERIAL
247 Allowed values: NONE, PPM, SERIAL, MSP, SPI, UIB
249 # get serialrx
250 serialrx_provider = SBUS
251 Allowed values: SPEK1024, SPEK2048, SBUS, SUMD, IBUS, JETIEXBUS, CRSF, FPORT, SBUS_FAST, FPORT2, SRXL2
255 ## Receiver configuration.
257 ### FrSky D4R-II
259 Set the RX for 'No Pulses'.  Turn OFF TX and RX, Turn ON RX.  Press and release F/S button on RX.  Turn off RX.
261 ### Graupner GR-24 PWM
263 Set failsafe on the throttle channel in the receiver settings (via transmitter menu) to a value below `rx_min_usec` using channel mode FAILSAFE.
264 This is the prefered way, since this is *much faster* detected by the FC then a channel that sends no pulses (OFF).
266 __NOTE:__
267 One or more control channels may be set to OFF to signal a failsafe condition to the FC, all other channels *must* be set to either HOLD or OFF.
268 Do __NOT USE__ the mode indicated with FAILSAFE instead, as this combination is NOT handled correctly by the FC.
270 ## Receiver Channel Range Configuration.
272 If you have a transmitter/receiver, that output a non-standard pulse range (i.e. 1070-1930 as some Spektrum receivers)
273 you could use rx channel range configuration to map actual range of your transmitter to 1000-2000 as expected by INAV.
275 The low and high value of a channel range are often referred to as 'End-points'.  e.g. 'End-point adjustments / EPA'.
277 All attempts should be made to configure your transmitter/receiver to use the range 1000-2000 *before* using this feature
278 as you will have less preceise control if it is used.
280 To do this you should figure out what range your transmitter outputs and use these values for rx range configuration.
281 You can do this in a few simple steps:
283 If you have used rc range configuration previously you should reset it to prevent it from altering rc input. Do so
284 by entering the following command in CLI:
286 rxrange reset
287 save
290 Now reboot your FC, connect the configurator, go to the `Receiver` tab move sticks on your transmitter and note min and
291 max values of first 4 channels. Take caution as you can accidentally arm your craft. Best way is to move one channel at
292 a time.
294 Go to CLI and set the min and max values with the following command:
296 rxrange <channel_number> <min> <max>
299 For example, if you have the range 1070-1930 for the first channel you should use `rxrange 0 1070 1930` in
300 the CLI. Be sure to enter the `save` command to save the settings.
302 After configuring channel ranges use the sub-trim on your transmitter to set the middle point of pitch, roll, yaw and throttle.
305 You can also use rxrange to reverse the direction of an input channel, e.g. `rxrange 0 2000 1000`.