Blackbox device type 'file' (SITL) considered working when file handler is available
[inav.git] / src / main / rx / rx.h
blob1aee04ec0833e3956e2d732d20ef936e56dc65d7
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #pragma once
20 #include <stdint.h>
21 #include <stdbool.h>
23 #include "common/time.h"
24 #include "common/tristate.h"
26 #include "config/parameter_group.h"
28 #define STICK_CHANNEL_COUNT 4
30 #define PWM_RANGE_MIN 1000
31 #define PWM_RANGE_MAX 2000
32 #define PWM_RANGE_MIDDLE (PWM_RANGE_MIN + ((PWM_RANGE_MAX - PWM_RANGE_MIN) / 2))
34 #define PWM_PULSE_MIN 750 // minimum PWM pulse width which is considered valid
35 #define PWM_PULSE_MAX 2250 // maximum PWM pulse width which is considered valid
37 #define MIDRC_MIN 1200
38 #define MIDRC_MAX 1700
40 #define RXFAIL_STEP_TO_CHANNEL_VALUE(step) (PWM_PULSE_MIN + 25 * step)
41 #define CHANNEL_VALUE_TO_RXFAIL_STEP(channelValue) ((constrain(channelValue, PWM_PULSE_MIN, PWM_PULSE_MAX) - PWM_PULSE_MIN) / 25)
42 #define MAX_RXFAIL_RANGE_STEP ((PWM_PULSE_MAX - PWM_PULSE_MIN) / 25)
44 #define DEFAULT_SERVO_MIN 1000
45 #define DEFAULT_SERVO_MIDDLE 1500
46 #define DEFAULT_SERVO_MAX 2000
48 #define DELAY_50_HZ (1000000 / 50)
49 #define DELAY_10_HZ (1000000 / 10)
50 #define DELAY_5_HZ (1000000 / 5)
52 #define RSSI_MAX_VALUE 1023
54 typedef enum {
55 RX_FRAME_PENDING = 0, // No new data available from receiver
56 RX_FRAME_COMPLETE = (1 << 0), // There is new data available
57 RX_FRAME_FAILSAFE = (1 << 1), // Receiver detected loss of RC link. Only valid when RX_FRAME_COMPLETE is set as well
58 RX_FRAME_PROCESSING_REQUIRED = (1 << 2),
59 RX_FRAME_DROPPED = (1 << 3), // Receiver detected dropped frame. Not loss of link yet.
60 } rxFrameState_e;
62 typedef enum {
63 RX_TYPE_NONE = 0,
64 RX_TYPE_SERIAL,
65 RX_TYPE_MSP,
66 RX_TYPE_SIM
67 } rxReceiverType_e;
69 typedef enum {
70 SERIALRX_SPEKTRUM1024 = 0,
71 SERIALRX_SPEKTRUM2048,
72 SERIALRX_SBUS,
73 SERIALRX_SUMD,
74 SERIALRX_IBUS,
75 SERIALRX_JETIEXBUS,
76 SERIALRX_CRSF,
77 SERIALRX_FPORT,
78 SERIALRX_SBUS_FAST,
79 SERIALRX_FPORT2,
80 SERIALRX_SRXL2,
81 SERIALRX_GHST,
82 SERIALRX_MAVLINK,
83 SERIALRX_FBUS,
84 } rxSerialReceiverType_e;
86 #ifdef USE_24CHANNELS
87 #define MAX_SUPPORTED_RC_CHANNEL_COUNT 26
88 #else
89 #define MAX_SUPPORTED_RC_CHANNEL_COUNT 18
90 #endif
92 #define NON_AUX_CHANNEL_COUNT 4
93 #define MAX_AUX_CHANNEL_COUNT (MAX_SUPPORTED_RC_CHANNEL_COUNT - NON_AUX_CHANNEL_COUNT)
95 extern const char rcChannelLetters[];
97 #define MAX_MAPPABLE_RX_INPUTS 4
99 #define MAX_INVALID_RX_PULSE_TIME 300
101 #define RSSI_VISIBLE_VALUE_MIN 0
102 #define RSSI_VISIBLE_VALUE_MAX 100
103 #define RSSI_VISIBLE_FACTOR (RSSI_MAX_VALUE/(float)RSSI_VISIBLE_VALUE_MAX)
105 typedef struct rxChannelRangeConfig_s {
106 uint16_t min;
107 uint16_t max;
108 } rxChannelRangeConfig_t;
109 PG_DECLARE_ARRAY(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeConfigs);
111 typedef struct rxConfig_s {
112 uint8_t receiverType; // RC receiver type (rxReceiverType_e enum)
113 uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order
114 uint8_t serialrx_provider; // Type of UART-based receiver (rxSerialReceiverType_e enum). Only used if receiverType is RX_TYPE_SERIAL
115 uint8_t serialrx_inverted; // Flip the default inversion of the protocol - e.g. sbus (Futaba, FrSKY) is inverted if this is false, uninverted if it's true. Support for uninverted OpenLRS (and modified FrSKY) receivers.
116 uint8_t halfDuplex; // allow rx to operate in half duplex mode. From tristate_e.
117 #ifdef USE_SPEKTRUM_BIND
118 uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers
119 uint8_t spektrum_sat_bind_autoreset; // whenever we will reset (exit) binding mode after hard reboot
120 #endif
121 uint8_t rssi_channel;
122 uint8_t rssiMin; // minimum RSSI sent by the RX - [RSSI_VISIBLE_VALUE_MIN, RSSI_VISIBLE_VALUE_MAX]
123 uint8_t rssiMax; // maximum RSSI sent by the RX - [RSSI_VISIBLE_VALUE_MIN, RSSI_VISIBLE_VALUE_MAX]
124 uint16_t sbusSyncInterval;
125 uint16_t mincheck; // minimum rc end
126 uint16_t maxcheck; // maximum rc end
127 uint16_t rx_min_usec;
128 uint16_t rx_max_usec;
129 uint8_t rcFilterFrequency; // RC filter cutoff frequency (smoothness vs response sharpness)
130 uint8_t autoSmooth; // auto smooth rx input (0 = off, 1 = on)
131 uint8_t autoSmoothFactor; // auto smooth rx input factor (1 = no smoothing, 100 = lots of smoothing)
132 uint16_t mspOverrideChannels; // Channels to override with MSP RC when BOXMSPRCOVERRIDE is active
133 uint8_t rssi_source;
134 #ifdef USE_SERIALRX_SRXL2
135 uint8_t srxl2_unit_id;
136 uint8_t srxl2_baud_fast;
137 #endif
138 } rxConfig_t;
140 PG_DECLARE(rxConfig_t, rxConfig);
142 #define REMAPPABLE_CHANNEL_COUNT ARRAYLEN(((rxConfig_t *)0)->rcmap)
144 typedef struct rxLinkQualityTracker_s {
145 timeMs_t lastUpdatedMs;
146 uint32_t lqAccumulator;
147 uint32_t lqCount;
148 uint32_t lqValue;
149 } rxLinkQualityTracker_e;
152 struct rxRuntimeConfig_s;
153 typedef struct rxRuntimeConfig_s rxRuntimeConfig_t;
155 typedef uint16_t (*rcReadRawDataFnPtr)(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
156 typedef uint8_t (*rcFrameStatusFnPtr)(rxRuntimeConfig_t *rxRuntimeConfig);
157 typedef bool (*rcProcessFrameFnPtr)(const rxRuntimeConfig_t *rxRuntimeConfig);
158 typedef uint16_t (*rcGetLinkQualityPtr)(const rxRuntimeConfig_t *rxRuntimeConfig);
160 typedef struct rxRuntimeConfig_s {
161 uint8_t channelCount; // number of rc channels as reported by current input driver
162 timeUs_t rxSignalTimeout;
163 rcReadRawDataFnPtr rcReadRawFn;
164 rcFrameStatusFnPtr rcFrameStatusFn;
165 rcProcessFrameFnPtr rcProcessFrameFn;
166 rxLinkQualityTracker_e * lqTracker; // Pointer to a
167 uint16_t *channelData;
168 void *frameData;
169 } rxRuntimeConfig_t;
171 typedef struct rcChannel_s {
172 int16_t raw; // Value received via RX - [1000;2000]
173 int16_t data; // Value after processing - [1000;2000]
174 timeMs_t expiresAt; // Time when this value becomes too old and it's discarded
175 } rcChannel_t;
177 typedef enum {
178 RSSI_SOURCE_NONE = 0,
179 RSSI_SOURCE_AUTO,
180 RSSI_SOURCE_ADC,
181 RSSI_SOURCE_RX_CHANNEL,
182 RSSI_SOURCE_RX_PROTOCOL,
183 RSSI_SOURCE_MSP,
184 } rssiSource_e;
186 typedef struct rxLinkStatistics_s {
187 int16_t uplinkRSSI; // RSSI value in dBm
188 uint8_t uplinkLQ; // A protocol specific measure of the link quality in [0..100]
189 int8_t uplinkSNR; // The SNR of the uplink in dB
190 uint8_t rfMode; // A protocol specific measure of the transmission bandwidth [2 = 150Hz, 1 = 50Hz, 0 = 4Hz]
191 uint16_t uplinkTXPower; // power in mW
192 uint8_t activeAntenna;
193 } rxLinkStatistics_t;
195 typedef uint16_t (*rcReadRawDataFnPtr)(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
196 typedef uint8_t (*rcFrameStatusFnPtr)(rxRuntimeConfig_t *rxRuntimeConfig);
197 typedef bool (*rcProcessFrameFnPtr)(const rxRuntimeConfig_t *rxRuntimeConfig);
198 typedef uint16_t (*rcGetLinkQualityPtr)(const rxRuntimeConfig_t *rxRuntimeConfig);
200 extern rxRuntimeConfig_t rxRuntimeConfig; //!!TODO remove this extern, only needed once for channelCount
201 extern rxLinkStatistics_t rxLinkStatistics;
202 void lqTrackerReset(rxLinkQualityTracker_e * lqTracker);
203 void lqTrackerAccumulate(rxLinkQualityTracker_e * lqTracker, uint16_t rawValue);
204 void lqTrackerSet(rxLinkQualityTracker_e * lqTracker, uint16_t rawValue);
205 uint16_t lqTrackerGet(rxLinkQualityTracker_e * lqTracker);
207 void rxInit(void);
208 void rxUpdateRSSISource(void);
209 bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime);
210 bool rxIsReceivingSignal(void);
211 bool rxAreFlightChannelsValid(void);
212 bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs);
213 bool isRxPulseValid(uint16_t pulseDuration);
215 uint8_t calculateChannelRemapping(const uint8_t *channelMap, uint8_t channelMapEntryCount, uint8_t channelToRemap);
216 void parseRcChannels(const char *input);
218 void setRSSIFromMSP(uint8_t newMspRssi);
219 void updateRSSI(timeUs_t currentTimeUs);
220 // Returns RSSI in [0, RSSI_MAX_VALUE] range.
221 uint16_t getRSSI(void);
222 rssiSource_e getRSSISource(void);
224 void resetAllRxChannelRangeConfigurations(void);
226 void suspendRxSignal(void);
227 void resumeRxSignal(void);
229 // Processed RC channel value. These values might include
230 // filtering and some extra processing like value holding
231 // during failsafe.
232 int16_t rxGetChannelValue(unsigned channelNumber);