2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
23 #include "drivers/io_types.h"
27 #define GET_FRAME_ERR_LPF_FREQUENCY(period) (1 / (period / 10.0f))
28 #define FRAME_ERR_RESAMPLE_US 100000
30 typedef struct rxConfig_s
{
31 uint8_t rcmap
[RX_MAPPABLE_CHANNEL_COUNT
]; // mapping of radio channels to internal RPYTA+ order
32 uint8_t serialrx_provider
; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first.
33 uint8_t serialrx_inverted
; // invert the serial RX protocol compared to it's default setting
34 uint8_t halfDuplex
; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3.
35 ioTag_t spektrum_bind_pin_override_ioTag
;
36 ioTag_t spektrum_bind_plug_ioTag
;
37 uint8_t spektrum_sat_bind
; // number of bind pulses for Spektrum satellite receivers
38 uint8_t spektrum_sat_bind_autoreset
; // whenever we will reset (exit) binding mode after hard reboot
42 uint16_t midrc
; // Some radios have not a neutral point centered on 1500. can be changed here
43 uint16_t mincheck
; // minimum rc end
44 uint16_t maxcheck
; // maximum rc end
45 uint8_t fpvCamAngleDegrees
; // Camera angle to be scaled into rc commands
46 uint8_t airModeActivateThreshold
; // Throttle setpoint percent where airmode gets activated
49 uint8_t max_aux_channel
;
50 uint8_t rssi_src_frame_errors
; // true to use frame drop flags in the rx protocol
51 int8_t rssi_offset
; // offset applied to the RSSI value before it is returned
52 uint8_t rc_smoothing_mode
; // Whether filter based rc smoothing is on or off
53 uint8_t rc_smoothing_setpoint_cutoff
; // Filter cutoff frequency for the setpoint filter (0 = auto)
54 uint8_t rc_smoothing_feedforward_cutoff
; // Filter cutoff frequency for the feedforward filter (0 = auto)
55 uint8_t rc_smoothing_throttle_cutoff
; // Filter cutoff frequency for the setpoint filter (0 = auto)
56 uint8_t rc_smoothing_debug_axis
; // Axis to log as debug values when debug_mode = RC_SMOOTHING
57 uint8_t rc_smoothing_auto_factor_rpy
; // Used to adjust the "smoothness" determined by the auto cutoff calculations
58 uint8_t rc_smoothing_auto_factor_throttle
; // Used to adjust the "smoothness" determined by the auto cutoff calculations
59 uint8_t rssi_src_frame_lpf_period
; // Period of the cutoff frequency for the source frame RSSI filter (in 0.1 s)
60 uint8_t srxl2_unit_id
; // Spektrum SRXL2 RX unit id
61 uint8_t srxl2_baud_fast
; // Select Spektrum SRXL2 fast baud rate
62 uint8_t sbus_baud_fast
; // Select SBus fast baud rate
63 uint8_t crsf_use_rx_snr
; // Use RX SNR (in dB) instead of RSSI dBm for CRSF
64 uint32_t msp_override_channels_mask
; // Channels to override when the MSP override mode is enabled
65 uint8_t crsf_use_negotiated_baud
; // Use negotiated baud rate for CRSF V3
68 PG_DECLARE(rxConfig_t
, rxConfig
);