Cleanup and blackbox changes
[inav.git] / docs / Rx.md
blobc52fe151571f0f824298a7c3e20fc32120280beb
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 a number of types of receivers:
7 * PPM Receivers (obsolete)
8 * Serial Receivers
9 * MSP RX
11 ## PPM Receivers
13 **Only supported in INAV 3.x and below**
15 PPM is sometimes known as PPM SUM or CPPM.
17 12 channels via a single input pin, not as accurate or jitter free as methods that use serial communications, but readily available.
19 These receivers are reported working:
21 FrSky D4R-II
22 http://www.frsky-rc.com/product/pro.php?pro_id=24
24 Graupner GR24
25 http://www.graupner.de/en/products/33512/product.aspx
27 R615X Spektrum/JR DSM2/DSMX Compatible 6Ch 2.4GHz Receiver w/CPPM
28 http://orangerx.com/2014/05/20/r615x-spektrumjr-dsm2dsmx-compatible-6ch-2-4ghz-receiver-wcppm-2/
30 FrSky D8R-XP 8ch telemetry receiver, or CPPM and RSSI enabled receiver
31 http://www.frsky-rc.com/product/pro.php?pro_id=21
33 ## Serial Receivers
35 *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*
37 ### Spektrum
39 This section describes the legacy Spektrum satellite capability; the newer SRXL2 protocol is described [later in this document](#srxl2) .
41 8 channels via serial currently supported.
43 These receivers are reported working:
45 Lemon Rx DSMX Compatible PPM 8-Channel Receiver + Lemon DSMX Compatible Satellite with Failsafe
46 http://www.lemon-rx.com/shop/index.php?route=product/product&product_id=118
49 #### Spektrum pesudo RSSI
51 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:
53 * Bind the satellite receiver using a physical RX; the bind function provided by the flight controller is not sufficient.
54 * The CLI variable `rssi_channel` is set to channel 9:
55 ```
56 set rssi_channel = 9
57 ```
58 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).
60 ### S.BUS
62 16 channels via serial currently supported.  See below how to set up your transmitter.
64 * 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.
65 * 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.
66 * 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.
67 * 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.
69 These receivers are reported working:
71 FrSky X4RSB 3/16ch Telemetry Receiver
72 http://www.frsky-rc.com/product/pro.php?pro_id=135
74 FrSky X8R 8/16ch Telemetry Receiver
75 http://www.frsky-rc.com/product/pro.php?pro_id=105
77 Futaba R2008SB 2.4GHz S-FHSS
78 http://www.futaba-rc.com/systems/futk8100-8j/
81 #### OpenTX S.BUS configuration
83 If using OpenTX set the transmitter module to D16 mode and ALSO select CH1-16 on the transmitter before binding to allow reception
84 of all 16 channels.
86 OpenTX 2.09, which is shipped on some Taranis X9D Plus transmitters, has a bug - [issue:1701](https://github.com/opentx/opentx/issues/1701).
87 The bug prevents use of all 16 channels.  Upgrade to the latest OpenTX version to allow correct reception of all 16 channels,
88 without the fix you are limited to 8 channels regardless of the CH1-16/D16 settings.
91 ### F.Port
93 F.Port is a protocol running on async serial allowing 16 controls channels and telemetry on a single UART.
95 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.
97 #### Connection
99 Just connect the S.Port wire from the receiver to the TX pad of a free UART on your flight controller
101 #### Configuration
103 For INAV 2.6 and newer versions, the default configuration should just work. However, if you're
104 upgrading from a previous version you might need to set the following settings to their
105 default values:
108 set serialrx_inverted = OFF
109 set serialrx_halfduplex = AUTO
112 For INAV versions prior to 2.6, you need to change the following settings:
115 set serialrx_inverted = ON
116 set serialrx_halfduplex = ON
119 ### SUMD
121 16 channels via serial currently supported.
123 These receivers are reported working:
125 GR-24 receiver HoTT
126 http://www.graupner.de/en/products/33512/product.aspx
128 Graupner receiver GR-12SH+ HoTT
129 http://www.graupner.de/en/products/870ade17-ace8-427f-943b-657040579906/33565/product.aspx
131 ### IBUS
133 10 channels via serial currently supported.
135 IBUS is the FlySky digital serial protocol and is available with the FS-IA6B, FS-X6B and FS-IA10 receivers.
136 The Turnigy TGY-IA6B and TGY-IA10 are the same devices with a different label, therefore they also work.
138 IBUS can provide up to 120Hz refresh rate, more than double compared to standard 50Hz of PPM.
140 FlySky FS-I6X TX natively supports 10ch.
142 If you are using a 6ch TX such as the FS-I6 or TGY-I6 then you must flash a 10ch
143 firmware on the TX to make use of these extra channels.
144 The flash is avaliable here: https://github.com/benb0jangles/FlySky-i6-Mod-
146      _______
147     /       \                               /------------\
148     | STM32 |-->UART RX-->[115200 baud]---->| Flysky RX  |
149     |  uC   |-  UART TX--x[not connected]   | IBUS-Servo |
150     \_______/                               \------------/
152 After flash "10ch Timer Mod i6 Updater", it is passible to get RSSI signal on selected Aux channel from FS-i6 Err sensor.
154 It is possible to use IBUS RX and IBUS telemetry on only one port of the hardware UART. More information in Telemetry.md.
156 ### SRXL2
158 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.
160 #### Wiring
162 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.
164 #### Configuration
166 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:
169 feature TELEMETRY
170 feature -RSSI_ADC
171 map TAER
172 set receiver_type = SERIAL
173 set serialrx_provider = SRXL2
174 set serialrx_inverted = OFF
175 set srxl2_unit_id = 1
176 set srxl2_baud_fast = ON
177 set rssi_source = PROTOCOL
178 set rssi_channel = 0
181 #### Notes:
183 * RSSI_ADC is disabled, as this would override the value provided through SRXL2
184 * `rssi_channel = 0` is required, unlike earlier Spektrum devices (e.g. SPM4649T).
186 Setting these values differently may have an adverse effects on RSSI readings.
188 #### CLI Bind Command
190 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.
193 bind_rx
196 ## MultiWii serial protocol (MSP RX)
198 Allows you to use MSP commands as the RC input. Up to 18 channels are supported.
199 Note:
200 * It is necessary to update `MSP_SET_RAW_RC` at 5Hz or faster.
201 * `MSP_SET_RAW_RC` uses the defined RC channel map
202 * `MSP_RC` returns `AERT` regardless of channel map
203 * You can combine "real" RC radio and MSP RX by compiling custom firmware with `USE_MSP_RC_OVERRIDE` defined. Then use `msp_override_channels` to set the channels to be overridden.
204 * The [wiki Remote Control and Management article](https://github.com/iNavFlight/inav/wiki/INAV-Remote-Management,-Control-and-Telemetry) provides more information, including links to 3rd party projects that exercise `MSP_SET_RAW_RC` and `USE_MSP_RC_OVERRIDE`
206 ## SIM (SITL) Joystick
208 Enables the use of a joystick in the INAV SITL with a flight simulator. See the [SITL documentation](SITL/SITL.md).
210 ## Configuration
212 The receiver type can be set from the configurator or CLI.
215 # get receiver_type
216 receiver_type = NONE
217 Allowed values: NONE, SERIAL, MSP, SIM (SITL)
220 ### RX signal-loss detection
222 The software has signal loss detection which is always enabled.  Signal loss detection is used for safety and failsafe reasons.
224 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.
226 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.
228 Signal loss can be detected when:
230 1. no rx data is received (due to radio reception, recevier configuration or cabling issues).
231 2. using Serial RX and receiver indicates failsafe condition.
232 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`.
234 #### `rx_min_usec`
236 The lowest channel value considered valid.  e.g. PWM/PPM pulse length
238 #### `rx_max_usec`
240 The highest channel value considered valid.  e.g. PWM/PPM pulse length
242 ### Serial RX
244 See the Serial chapter for some some RX configuration examples.
246 To setup spectrum in the GUI:
247 1. Start on the "Ports" tab make sure that teh required has serial RX.  If not set the checkbox, save and reboot.
248 2. Move to the "Configuration" page and in the upper lefthand corner choose Serial RX as the receiver type.
249 3. Below that choose the type of serial receiver that you are using.  Save and reboot.
251 #### Using CLI:
253 For Serial RX set the `receiver_type` and `serialrx_provider` setting as appropriate for your RX.
256 # get rec
257 receiver_type = SERIAL
258 Allowed values: NONE, SERIAL, MSP, SIM (SITL)
260 # get serialrx
261 serialrx_provider = SBUS
262 Allowed values: SPEK1024, SPEK2048, SBUS, SUMD, IBUS, JETIEXBUS, CRSF, FPORT, SBUS_FAST, FPORT2, SRXL2, GHST, MAVLINK, FBUS
266 ## Receiver configuration.
268 ### FrSky D4R-II
270 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.
272 ### Graupner GR-24 PWM
274 Set failsafe on the throttle channel in the receiver settings (via transmitter menu) to a value below `rx_min_usec` using channel mode FAILSAFE.
275 This is the prefered way, since this is *much faster* detected by the FC then a channel that sends no pulses (OFF).
277 __NOTE:__
278 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.
279 Do __NOT USE__ the mode indicated with FAILSAFE instead, as this combination is NOT handled correctly by the FC.
281 ## Receiver Channel Range Configuration.
283 If you have a transmitter/receiver, that output a non-standard pulse range (i.e. 1070-1930 as some Spektrum receivers)
284 you could use rx channel range configuration to map actual range of your transmitter to 1000-2000 as expected by INAV.
286 The low and high value of a channel range are often referred to as 'End-points'.  e.g. 'End-point adjustments / EPA'.
288 All attempts should be made to configure your transmitter/receiver to use the range 1000-2000 *before* using this feature
289 as you will have less preceise control if it is used.
291 To do this you should figure out what range your transmitter outputs and use these values for rx range configuration.
292 You can do this in a few simple steps:
294 If you have used rc range configuration previously you should reset it to prevent it from altering rc input. Do so
295 by entering the following command in CLI:
297 rxrange reset
298 save
301 Now reboot your FC, connect the configurator, go to the `Receiver` tab move sticks on your transmitter and note min and
302 max values of first 4 channels. Take caution as you can accidentally arm your craft. Best way is to move one channel at
303 a time.
305 Go to CLI and set the min and max values with the following command:
307 rxrange <channel_number> <min> <max>
310 For example, if you have the range 1070-1930 for the first channel you should use `rxrange 0 1070 1930` in
311 the CLI. Be sure to enter the `save` command to save the settings.
313 After configuring channel ranges use the sub-trim on your transmitter to set the middle point of pitch, roll, yaw and throttle.
316 You can also use rxrange to reverse the direction of an input channel, e.g. `rxrange 0 2000 1000`.